Tools: factor init up into parent class

Tools: autotest: use speedup 8 for all suites

for reliability
This commit is contained in:
Peter Barker 2019-03-09 15:20:36 +11:00 committed by Peter Barker
parent 844999c458
commit d53f787a14
7 changed files with 139 additions and 392 deletions

View File

@ -12,39 +12,18 @@ import operator
# get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__))
HOME = mavutil.location(-27.274439, 151.290064, 343, 8.7)
SITL_START_LOCATION = mavutil.location(-27.274439, 151.290064, 343, 8.7)
class AutoTestTracker(AutoTest):
def __init__(self,
binary,
valgrind=False,
gdb=False,
speedup=10,
frame=None,
params=None,
gdbserver=False,
breakpoints=[],
**kwargs):
super(AutoTestTracker, self).__init__(**kwargs)
self.binary = binary
self.valgrind = valgrind
self.gdb = gdb
self.frame = frame
self.params = params
self.gdbserver = gdbserver
self.breakpoints = breakpoints
self.home = "%f,%f,%u,%u" % (HOME.lat,
HOME.lng,
HOME.alt,
HOME.heading)
self.homeloc = None
self.speedup = speedup
def log_name(self):
return "AntennaTracker"
self.log_name = "AntennaTracker"
self.logfile = None
def test_filepath(self):
return os.path.realpath(__file__)
self.sitl = None
def sitl_start_location(self):
return SITL_START_LOCATION
def start_stream_systemtime(self):
'''AntennaTracker doesn't stream this by default but we need it for get_sim_time'''
@ -68,43 +47,12 @@ class AutoTestTracker(AutoTest):
def is_tracker(self):
return True
def init(self):
if self.frame is None:
self.frame = "tracker"
def default_frame(self):
return "tracker"
self.mavproxy_logfile = self.open_mavproxy_logfile()
self.sitl = util.start_SITL(self.binary,
wipe=True,
model=self.frame,
home=self.home,
speedup=self.speedup,
valgrind=self.valgrind,
gdb=self.gdb,
gdbserver=self.gdbserver,
breakpoints=self.breakpoints,
)
self.mavproxy = util.start_MAVProxy_SITL(
'AntennaTracker',
logfile=self.mavproxy_logfile,
options=self.mavproxy_options())
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
self.logfile = self.mavproxy.match.group(1)
self.progress("LOGFILE %s" % self.logfile)
self.try_symlink_tlog()
self.mavproxy.expect('Received [0-9]+ parameters')
util.expect_setup_callback(self.mavproxy, self.expect_callback)
self.expect_list_clear()
self.expect_list_extend([self.sitl, self.mavproxy])
self.progress("Started simulator")
self.get_mavlink_connection_going()
self.progress("Ready to start testing!")
def apply_defaultfile_parameters(self):
# tracker doesn't have a default parameters file
pass
def sysid_thismav(self):
return 2

View File

@ -28,74 +28,18 @@ SITL_START_LOCATION = mavutil.location(40.071374969556928,
class AutoTestRover(AutoTest):
def __init__(self,
binary,
valgrind=False,
gdb=False,
speedup=8,
frame=None,
params=None,
gdbserver=False,
breakpoints=[],
**kwargs):
super(AutoTestRover, self).__init__(**kwargs)
self.binary = binary
self.valgrind = valgrind
self.gdb = gdb
self.frame = frame
self.params = params
self.gdbserver = gdbserver
self.breakpoints = breakpoints
self.speedup = speedup
def log_name(self):
return "APMrover2"
self.sitl = None
self.log_name = "APMrover2"
def test_filepath(self):
return os.path.realpath(__file__)
def sitl_start_location(self):
return SITL_START_LOCATION
def init(self):
super(AutoTestRover, self).init(os.path.realpath(__file__))
if self.frame is None:
self.frame = 'rover'
self.mavproxy_logfile = self.open_mavproxy_logfile()
self.sitl = util.start_SITL(self.binary,
model=self.frame,
home=self.sitl_home(),
speedup=self.speedup,
valgrind=self.valgrind,
gdb=self.gdb,
gdbserver=self.gdbserver,
breakpoints=self.breakpoints,
wipe=True)
self.mavproxy = util.start_MAVProxy_SITL(
'APMrover2',
logfile=self.mavproxy_logfile,
options=self.mavproxy_options())
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
self.logfile = self.mavproxy.match.group(1)
self.progress("LOGFILE %s" % self.logfile)
self.try_symlink_tlog()
self.progress("WAITING FOR PARAMETERS")
self.mavproxy.expect('Received [0-9]+ parameters')
util.expect_setup_callback(self.mavproxy, self.expect_callback)
self.expect_list_clear()
self.expect_list_extend([self.sitl, self.mavproxy])
self.progress("Started simulator")
self.get_mavlink_connection_going()
self.apply_defaultfile_parameters()
self.progress("Ready to start testing!")
def default_frame(self):
return "rover"
def is_rover(self):
return True

View File

@ -33,29 +33,12 @@ SITL_START_LOCATION_AVC = mavutil.location(40.072842, -105.230575, 1586, 0)
class AutoTestCopter(AutoTest):
def __init__(self, binary,
valgrind=False,
gdb=False,
speedup=10,
frame=None,
params=None,
gdbserver=False,
breakpoints=[],
**kwargs):
super(AutoTestCopter, self).__init__(**kwargs)
self.binary = binary
self.valgrind = valgrind
self.gdb = gdb
self.frame = frame
self.params = params
self.gdbserver = gdbserver
self.breakpoints = breakpoints
self.speedup = speedup
def log_name(self):
return "ArduCopter"
self.log_name = "ArduCopter"
self.sitl = None
def test_filepath(self):
return os.path.realpath(__file__)
def sitl_start_location(self):
return SITL_START_LOCATION
@ -72,48 +55,11 @@ class AutoTestCopter(AutoTest):
def vehicleinfo_key(self):
return 'ArduCopter'
def init(self):
super(AutoTestCopter, self).init(os.path.realpath(__file__))
if self.frame is None:
self.frame = '+'
def default_frame(self):
return "+"
self.mavproxy_logfile = self.open_mavproxy_logfile()
self.sitl = util.start_SITL(self.binary,
model=self.frame,
home=self.sitl_home(),
speedup=self.speedup,
valgrind=self.valgrind,
gdb=self.gdb,
gdbserver=self.gdbserver,
breakpoints=self.breakpoints,
vicon=True,
wipe=True)
self.mavproxy = util.start_MAVProxy_SITL(
'ArduCopter',
logfile=self.mavproxy_logfile,
options=self.mavproxy_options())
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
self.logfile = self.mavproxy.match.group(1)
self.progress("LOGFILE %s" % self.logfile)
self.try_symlink_tlog()
self.progress("WAITING FOR PARAMETERS")
self.mavproxy.expect('Received [0-9]+ parameters')
self.get_mavlink_connection_going()
self.apply_defaultfile_parameters()
util.expect_setup_callback(self.mavproxy, self.expect_callback)
self.expect_list_clear()
self.expect_list_extend([self.sitl, self.mavproxy])
self.progress("Started simulator")
self.progress("Ready to start testing!")
def uses_vicon(self):
return True
def close(self):
super(AutoTestCopter, self).close()
@ -2999,12 +2945,11 @@ class AutoTestCopter(AutoTest):
class AutoTestHeli(AutoTestCopter):
def __init__(self, *args, **kwargs):
def log_name(self):
return "HeliCopter"
super(AutoTestHeli, self).__init__(*args, **kwargs)
self.log_name = "HeliCopter"
self.frame = 'heli'
def default_frame(self):
return "heli"
def sitl_start_location(self):
return SITL_START_LOCATION_AVC

View File

@ -23,75 +23,26 @@ WIND = "0,180,0.2" # speed,direction,variance
class AutoTestPlane(AutoTest):
def __init__(self,
binary,
valgrind=False,
gdb=False,
speedup=10,
frame=None,
params=None,
gdbserver=False,
breakpoints=[],
**kwargs):
super(AutoTestPlane, self).__init__(**kwargs)
self.binary = binary
self.valgrind = valgrind
self.gdb = gdb
self.frame = frame
self.params = params
self.gdbserver = gdbserver
self.breakpoints = breakpoints
self.homeloc = None
self.speedup = speedup
def log_name(self):
return "ArduPlane"
self.sitl = None
self.log_name = "ArduPlane"
def test_filepath(self):
return os.path.realpath(__file__)
def sitl_start_location(self):
return SITL_START_LOCATION
def init(self):
super(AutoTestPlane, self).init(os.path.realpath(__file__))
if self.frame is None:
self.frame = 'plane-elevrev'
def defaults_filepath(self):
return os.path.join(testdir, 'default_params/plane-jsbsim.parm')
self.mavproxy_logfile = self.open_mavproxy_logfile()
def default_frame(self):
return "plane-elevrev"
defaults_file = os.path.join(testdir,
'default_params/plane-jsbsim.parm')
self.sitl = util.start_SITL(self.binary,
wipe=True,
model=self.frame,
home=self.sitl_home(),
speedup=self.speedup,
defaults_file=defaults_file,
valgrind=self.valgrind,
gdb=self.gdb,
gdbserver=self.gdbserver,
breakpoints=self.breakpoints)
self.mavproxy = util.start_MAVProxy_SITL(
'ArduPlane',
logfile=self.mavproxy_logfile,
options=self.mavproxy_options())
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
self.logfile = self.mavproxy.match.group(1)
self.progress("LOGFILE %s" % self.logfile)
self.try_symlink_tlog()
self.mavproxy.expect('Received [0-9]+ parameters')
util.expect_setup_callback(self.mavproxy, self.expect_callback)
self.expect_list_clear()
self.expect_list_extend([self.sitl, self.mavproxy])
self.progress("Started simulator")
self.get_mavlink_connection_going()
self.progress("Ready to start testing!")
def apply_defaultfile_parameters(self):
# plane passes in a defaults_file in place of applying
# parameters afterwards.
pass
def is_plane(self):
return True

View File

@ -12,37 +12,15 @@ from pysim import util
from common import AutoTest
from common import NotAchievedException
# get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__))
SITL_START_LOCATION = mavutil.location(33.810313, -118.393867, 0, 185)
class AutoTestSub(AutoTest):
def __init__(self,
binary,
valgrind=False,
gdb=False,
speedup=10,
frame=None,
params=None,
gdbserver=False,
breakpoints=[],
**kwargs):
super(AutoTestSub, self).__init__(**kwargs)
self.binary = binary
self.valgrind = valgrind
self.gdb = gdb
self.frame = frame
self.params = params
self.gdbserver = gdbserver
self.breakpoints = breakpoints
self.speedup = speedup
def log_name(self):
return "ArduSub"
self.sitl = None
self.log_name = "ArduSub"
def test_filepath(self):
return os.path.realpath(__file__)
def default_mode(self):
return 'MANUAL'
@ -50,50 +28,15 @@ class AutoTestSub(AutoTest):
def sitl_start_location(self):
return SITL_START_LOCATION
def default_frame(self):
return 'vectored'
def init(self):
super(AutoTestSub, self).init(os.path.realpath(__file__))
if self.frame is None:
self.frame = 'vectored'
self.mavproxy_logfile = self.open_mavproxy_logfile()
self.sitl = util.start_SITL(self.binary,
model=self.frame,
home=self.sitl_home(),
speedup=self.speedup,
valgrind=self.valgrind,
gdb=self.gdb,
gdbserver=self.gdbserver,
breakpoints=self.breakpoints,
wipe=True)
self.mavproxy = util.start_MAVProxy_SITL(
'ArduSub',
logfile=self.mavproxy_logfile,
options=self.mavproxy_options())
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
self.logfile = self.mavproxy.match.group(1)
self.progress("LOGFILE %s" % self.logfile)
self.try_symlink_tlog()
self.progress("WAITING FOR PARAMETERS")
self.mavproxy.expect('Received [0-9]+ parameters')
util.expect_setup_callback(self.mavproxy, self.expect_callback)
self.expect_list_clear()
self.expect_list_extend([self.sitl, self.mavproxy])
self.progress("Started simulator")
self.get_mavlink_connection_going()
self.apply_defaultfile_parameters()
super(AutoTestSub, self).init()
# FIXME:
self.set_parameter("FS_GCS_ENABLE", 0)
self.progress("Ready to start testing!")
def is_sub(self):
return True

View File

@ -154,9 +154,27 @@ class AutoTest(ABC):
It implements the common function for all vehicle types.
"""
def __init__(self,
binary,
valgrind=False,
gdb=False,
speedup=8,
frame=None,
params=None,
gdbserver=False,
breakpoints=[],
viewerip=None,
use_map=False,
_show_test_timings=False):
self.binary = binary
self.valgrind = valgrind
self.gdb = gdb
self.frame = frame
self.params = params
self.gdbserver = gdbserver
self.breakpoints = breakpoints
self.speedup = speedup
self.mavproxy = None
self.mav = None
self.viewerip = viewerip
@ -231,7 +249,7 @@ class AutoTest(ABC):
return ret
def vehicleinfo_key(self):
return self.log_name
return self.log_name()
def repeatedly_apply_parameter_file(self, filepath):
'''keep applying a parameter file until no parameters changed'''
@ -249,6 +267,7 @@ class AutoTest(ABC):
def apply_defaultfile_parameters(self):
"""Apply parameter file."""
self.progress("Applying default parameters file")
# setup test parameters
vinfo = vehicleinfo.VehicleInfo()
if self.params is None:
@ -337,7 +356,7 @@ class AutoTest(ABC):
os.chmod(valgrind_log, 0o644)
shutil.copy(valgrind_log,
self.buildlogs_path("%s-valgrind.log" %
self.log_name))
self.log_name()))
def start_test(self, description):
self.progress("#")
@ -345,7 +364,7 @@ class AutoTest(ABC):
self.progress("#")
def try_symlink_tlog(self):
self.buildlog = self.buildlogs_path(self.log_name + "-test.tlog")
self.buildlog = self.buildlogs_path(self.log_name() + "-test.tlog")
self.progress("buildlog=%s" % self.buildlog)
if os.path.exists(self.buildlog):
os.unlink(self.buildlog)
@ -1677,7 +1696,7 @@ class AutoTest(ABC):
def run_one_test(self, name, desc, test_function, interact=False):
'''new-style run-one-test used by run_tests'''
test_output_filename = self.buildlogs_path("%s-%s.txt" %
(self.log_name, name))
(self.log_name(), name))
tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile)
prettyname = "%s (%s)" % (name, desc)
@ -1735,9 +1754,58 @@ class AutoTest(ABC):
exit(1)
self.progress("PASSED: Check for syntax mistake in autotest lambda")
def init(self, file):
def uses_vicon(self):
return False
def defaults_filepath(self):
return None
def init(self):
"""Initilialize autotest feature."""
self.check_test_syntax(test_file=os.path.realpath(file))
self.check_test_syntax(test_file=self.test_filepath())
self.mavproxy_logfile = self.open_mavproxy_logfile()
if self.frame is None:
self.frame = self.default_frame()
self.progress("Starting simulator")
self.sitl = util.start_SITL(self.binary,
breakpoints=self.breakpoints,
defaults_file=self.defaults_filepath(),
gdb=self.gdb,
gdbserver=self.gdbserver,
home=self.sitl_home(),
model=self.frame,
speedup=self.speedup,
valgrind=self.valgrind,
vicon=self.uses_vicon(),
wipe=True,
)
self.progress("Starting MAVProxy")
self.mavproxy = util.start_MAVProxy_SITL(
self.vehicleinfo_key(),
logfile=self.mavproxy_logfile,
options=self.mavproxy_options())
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
self.logfile = self.mavproxy.match.group(1)
self.progress("LOGFILE %s" % self.logfile)
self.try_symlink_tlog()
self.progress("Waiting for Parameters")
self.mavproxy.expect('Received [0-9]+ parameters')
self.progress("Starting MAVLink connection")
self.get_mavlink_connection_going()
self.apply_defaultfile_parameters()
util.expect_setup_callback(self.mavproxy, self.expect_callback)
self.expect_list_clear()
self.expect_list_extend([self.sitl, self.mavproxy])
self.progress("Ready to start testing!")
def poll_home_position(self, quiet=False):

View File

@ -13,87 +13,35 @@ import operator
# get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__))
HOME = mavutil.location(-27.274439, 151.290064, 343, 8.7)
SITL_START_LOCATION = mavutil.location(-27.274439, 151.290064, 343, 8.7)
MISSION = 'ArduPlane-Missions/Dalby-OBC2016.txt'
FENCE = 'ArduPlane-Missions/Dalby-OBC2016-fence.txt'
WIND = "0,180,0.2" # speed,direction,variance
class AutoTestQuadPlane(AutoTest):
def __init__(self,
binary,
valgrind=False,
gdb=False,
speedup=10,
frame=None,
params=None,
gdbserver=False,
breakpoints=[],
**kwargs):
super(AutoTestQuadPlane, self).__init__(**kwargs)
self.binary = binary
self.valgrind = valgrind
self.gdb = gdb
self.frame = frame
self.params = params
self.gdbserver = gdbserver
self.breakpoints = breakpoints
self.home = "%f,%f,%u,%u" % (HOME.lat,
HOME.lng,
HOME.alt,
HOME.heading)
self.homeloc = None
self.speedup = speedup
def default_frame(self):
return "quadplane"
self.log_name = "QuadPlane"
self.logfile = None
def test_filepath(self):
return os.path.realpath(__file__)
self.sitl = None
def sitl_start_location(self):
return SITL_START_LOCATION
def init(self):
super(AutoTestQuadPlane, self).init(os.path.realpath(__file__))
if self.frame is None:
self.frame = 'quadplane'
def log_name(self):
return "QuadPlane"
self.mavproxy_logfile = self.open_mavproxy_logfile()
def apply_defaultfile_parameters(self):
# plane passes in a defaults_file in place of applying
# parameters afterwards.
pass
def defaults_filepath(self):
vinfo = vehicleinfo.VehicleInfo()
defaults_file = vinfo.options["ArduPlane"]["frames"][self.frame]["default_params_filename"]
defaults_filepath = os.path.join(testdir, defaults_file)
self.sitl = util.start_SITL(self.binary,
wipe=True,
model=self.frame,
home=self.home,
speedup=self.speedup,
defaults_file=defaults_filepath,
valgrind=self.valgrind,
gdb=self.gdb,
gdbserver=self.gdbserver,
breakpoints=self.breakpoints,
)
self.mavproxy = util.start_MAVProxy_SITL(
'QuadPlane',
logfile=self.mavproxy_logfile,
options=self.mavproxy_options())
self.mavproxy.expect('Telemetry log: (\S+)\r\n')
self.logfile = self.mavproxy.match.group(1)
self.progress("LOGFILE %s" % self.logfile)
self.try_symlink_tlog()
self.mavproxy.expect('Received [0-9]+ parameters')
util.expect_setup_callback(self.mavproxy, self.expect_callback)
self.expect_list_clear()
self.expect_list_extend([self.sitl, self.mavproxy])
self.progress("Started simulator")
self.get_mavlink_connection_going()
self.progress("Ready to start testing!")
return os.path.join(testdir, defaults_file)
def is_plane(self):
return True