mirror of https://github.com/ArduPilot/ardupilot
Tools: factor init up into parent class
Tools: autotest: use speedup 8 for all suites for reliability
This commit is contained in:
parent
844999c458
commit
d53f787a14
|
@ -12,39 +12,18 @@ import operator
|
||||||
|
|
||||||
# get location of scripts
|
# get location of scripts
|
||||||
testdir = os.path.dirname(os.path.realpath(__file__))
|
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):
|
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,
|
def log_name(self):
|
||||||
HOME.lng,
|
return "AntennaTracker"
|
||||||
HOME.alt,
|
|
||||||
HOME.heading)
|
|
||||||
self.homeloc = None
|
|
||||||
self.speedup = speedup
|
|
||||||
|
|
||||||
self.log_name = "AntennaTracker"
|
def test_filepath(self):
|
||||||
self.logfile = None
|
return os.path.realpath(__file__)
|
||||||
|
|
||||||
self.sitl = None
|
def sitl_start_location(self):
|
||||||
|
return SITL_START_LOCATION
|
||||||
|
|
||||||
def start_stream_systemtime(self):
|
def start_stream_systemtime(self):
|
||||||
'''AntennaTracker doesn't stream this by default but we need it for get_sim_time'''
|
'''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):
|
def is_tracker(self):
|
||||||
return True
|
return True
|
||||||
|
|
||||||
def init(self):
|
def default_frame(self):
|
||||||
if self.frame is None:
|
return "tracker"
|
||||||
self.frame = "tracker"
|
|
||||||
|
|
||||||
self.mavproxy_logfile = self.open_mavproxy_logfile()
|
def apply_defaultfile_parameters(self):
|
||||||
|
# tracker doesn't have a default parameters file
|
||||||
self.sitl = util.start_SITL(self.binary,
|
pass
|
||||||
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 sysid_thismav(self):
|
def sysid_thismav(self):
|
||||||
return 2
|
return 2
|
||||||
|
|
|
@ -28,74 +28,18 @@ SITL_START_LOCATION = mavutil.location(40.071374969556928,
|
||||||
|
|
||||||
|
|
||||||
class AutoTestRover(AutoTest):
|
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
|
def test_filepath(self):
|
||||||
|
return os.path.realpath(__file__)
|
||||||
self.log_name = "APMrover2"
|
|
||||||
|
|
||||||
def sitl_start_location(self):
|
def sitl_start_location(self):
|
||||||
return SITL_START_LOCATION
|
return SITL_START_LOCATION
|
||||||
|
|
||||||
def init(self):
|
def default_frame(self):
|
||||||
super(AutoTestRover, self).init(os.path.realpath(__file__))
|
return "rover"
|
||||||
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 is_rover(self):
|
def is_rover(self):
|
||||||
return True
|
return True
|
||||||
|
|
|
@ -33,29 +33,12 @@ SITL_START_LOCATION_AVC = mavutil.location(40.072842, -105.230575, 1586, 0)
|
||||||
|
|
||||||
|
|
||||||
class AutoTestCopter(AutoTest):
|
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"
|
def test_filepath(self):
|
||||||
|
return os.path.realpath(__file__)
|
||||||
self.sitl = None
|
|
||||||
|
|
||||||
def sitl_start_location(self):
|
def sitl_start_location(self):
|
||||||
return SITL_START_LOCATION
|
return SITL_START_LOCATION
|
||||||
|
@ -72,48 +55,11 @@ class AutoTestCopter(AutoTest):
|
||||||
def vehicleinfo_key(self):
|
def vehicleinfo_key(self):
|
||||||
return 'ArduCopter'
|
return 'ArduCopter'
|
||||||
|
|
||||||
def init(self):
|
def default_frame(self):
|
||||||
super(AutoTestCopter, self).init(os.path.realpath(__file__))
|
return "+"
|
||||||
if self.frame is None:
|
|
||||||
self.frame = '+'
|
|
||||||
|
|
||||||
self.mavproxy_logfile = self.open_mavproxy_logfile()
|
def uses_vicon(self):
|
||||||
|
return True
|
||||||
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 close(self):
|
def close(self):
|
||||||
super(AutoTestCopter, self).close()
|
super(AutoTestCopter, self).close()
|
||||||
|
@ -2999,12 +2945,11 @@ class AutoTestCopter(AutoTest):
|
||||||
|
|
||||||
class AutoTestHeli(AutoTestCopter):
|
class AutoTestHeli(AutoTestCopter):
|
||||||
|
|
||||||
def __init__(self, *args, **kwargs):
|
def log_name(self):
|
||||||
|
return "HeliCopter"
|
||||||
|
|
||||||
super(AutoTestHeli, self).__init__(*args, **kwargs)
|
def default_frame(self):
|
||||||
|
return "heli"
|
||||||
self.log_name = "HeliCopter"
|
|
||||||
self.frame = 'heli'
|
|
||||||
|
|
||||||
def sitl_start_location(self):
|
def sitl_start_location(self):
|
||||||
return SITL_START_LOCATION_AVC
|
return SITL_START_LOCATION_AVC
|
||||||
|
|
|
@ -23,75 +23,26 @@ WIND = "0,180,0.2" # speed,direction,variance
|
||||||
|
|
||||||
|
|
||||||
class AutoTestPlane(AutoTest):
|
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
|
def log_name(self):
|
||||||
self.speedup = speedup
|
return "ArduPlane"
|
||||||
|
|
||||||
self.sitl = None
|
def test_filepath(self):
|
||||||
|
return os.path.realpath(__file__)
|
||||||
self.log_name = "ArduPlane"
|
|
||||||
|
|
||||||
def sitl_start_location(self):
|
def sitl_start_location(self):
|
||||||
return SITL_START_LOCATION
|
return SITL_START_LOCATION
|
||||||
|
|
||||||
def init(self):
|
def defaults_filepath(self):
|
||||||
super(AutoTestPlane, self).init(os.path.realpath(__file__))
|
return os.path.join(testdir, 'default_params/plane-jsbsim.parm')
|
||||||
if self.frame is None:
|
|
||||||
self.frame = 'plane-elevrev'
|
|
||||||
|
|
||||||
self.mavproxy_logfile = self.open_mavproxy_logfile()
|
def default_frame(self):
|
||||||
|
return "plane-elevrev"
|
||||||
|
|
||||||
defaults_file = os.path.join(testdir,
|
def apply_defaultfile_parameters(self):
|
||||||
'default_params/plane-jsbsim.parm')
|
# plane passes in a defaults_file in place of applying
|
||||||
self.sitl = util.start_SITL(self.binary,
|
# parameters afterwards.
|
||||||
wipe=True,
|
pass
|
||||||
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 is_plane(self):
|
def is_plane(self):
|
||||||
return True
|
return True
|
||||||
|
|
|
@ -12,37 +12,15 @@ from pysim import util
|
||||||
from common import AutoTest
|
from common import AutoTest
|
||||||
from common import NotAchievedException
|
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)
|
SITL_START_LOCATION = mavutil.location(33.810313, -118.393867, 0, 185)
|
||||||
|
|
||||||
|
|
||||||
class AutoTestSub(AutoTest):
|
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
|
def test_filepath(self):
|
||||||
|
return os.path.realpath(__file__)
|
||||||
self.log_name = "ArduSub"
|
|
||||||
|
|
||||||
def default_mode(self):
|
def default_mode(self):
|
||||||
return 'MANUAL'
|
return 'MANUAL'
|
||||||
|
@ -50,50 +28,15 @@ class AutoTestSub(AutoTest):
|
||||||
def sitl_start_location(self):
|
def sitl_start_location(self):
|
||||||
return SITL_START_LOCATION
|
return SITL_START_LOCATION
|
||||||
|
|
||||||
|
def default_frame(self):
|
||||||
|
return 'vectored'
|
||||||
|
|
||||||
def init(self):
|
def init(self):
|
||||||
super(AutoTestSub, self).init(os.path.realpath(__file__))
|
super(AutoTestSub, self).init()
|
||||||
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()
|
|
||||||
|
|
||||||
# FIXME:
|
# FIXME:
|
||||||
self.set_parameter("FS_GCS_ENABLE", 0)
|
self.set_parameter("FS_GCS_ENABLE", 0)
|
||||||
|
|
||||||
self.progress("Ready to start testing!")
|
|
||||||
|
|
||||||
def is_sub(self):
|
def is_sub(self):
|
||||||
return True
|
return True
|
||||||
|
|
||||||
|
|
|
@ -154,9 +154,27 @@ class AutoTest(ABC):
|
||||||
It implements the common function for all vehicle types.
|
It implements the common function for all vehicle types.
|
||||||
"""
|
"""
|
||||||
def __init__(self,
|
def __init__(self,
|
||||||
|
binary,
|
||||||
|
valgrind=False,
|
||||||
|
gdb=False,
|
||||||
|
speedup=8,
|
||||||
|
frame=None,
|
||||||
|
params=None,
|
||||||
|
gdbserver=False,
|
||||||
|
breakpoints=[],
|
||||||
viewerip=None,
|
viewerip=None,
|
||||||
use_map=False,
|
use_map=False,
|
||||||
_show_test_timings=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.mavproxy = None
|
||||||
self.mav = None
|
self.mav = None
|
||||||
self.viewerip = viewerip
|
self.viewerip = viewerip
|
||||||
|
@ -231,7 +249,7 @@ class AutoTest(ABC):
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
def vehicleinfo_key(self):
|
def vehicleinfo_key(self):
|
||||||
return self.log_name
|
return self.log_name()
|
||||||
|
|
||||||
def repeatedly_apply_parameter_file(self, filepath):
|
def repeatedly_apply_parameter_file(self, filepath):
|
||||||
'''keep applying a parameter file until no parameters changed'''
|
'''keep applying a parameter file until no parameters changed'''
|
||||||
|
@ -249,6 +267,7 @@ class AutoTest(ABC):
|
||||||
|
|
||||||
def apply_defaultfile_parameters(self):
|
def apply_defaultfile_parameters(self):
|
||||||
"""Apply parameter file."""
|
"""Apply parameter file."""
|
||||||
|
self.progress("Applying default parameters file")
|
||||||
# setup test parameters
|
# setup test parameters
|
||||||
vinfo = vehicleinfo.VehicleInfo()
|
vinfo = vehicleinfo.VehicleInfo()
|
||||||
if self.params is None:
|
if self.params is None:
|
||||||
|
@ -337,7 +356,7 @@ class AutoTest(ABC):
|
||||||
os.chmod(valgrind_log, 0o644)
|
os.chmod(valgrind_log, 0o644)
|
||||||
shutil.copy(valgrind_log,
|
shutil.copy(valgrind_log,
|
||||||
self.buildlogs_path("%s-valgrind.log" %
|
self.buildlogs_path("%s-valgrind.log" %
|
||||||
self.log_name))
|
self.log_name()))
|
||||||
|
|
||||||
def start_test(self, description):
|
def start_test(self, description):
|
||||||
self.progress("#")
|
self.progress("#")
|
||||||
|
@ -345,7 +364,7 @@ class AutoTest(ABC):
|
||||||
self.progress("#")
|
self.progress("#")
|
||||||
|
|
||||||
def try_symlink_tlog(self):
|
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)
|
self.progress("buildlog=%s" % self.buildlog)
|
||||||
if os.path.exists(self.buildlog):
|
if os.path.exists(self.buildlog):
|
||||||
os.unlink(self.buildlog)
|
os.unlink(self.buildlog)
|
||||||
|
@ -1677,7 +1696,7 @@ class AutoTest(ABC):
|
||||||
def run_one_test(self, name, desc, test_function, interact=False):
|
def run_one_test(self, name, desc, test_function, interact=False):
|
||||||
'''new-style run-one-test used by run_tests'''
|
'''new-style run-one-test used by run_tests'''
|
||||||
test_output_filename = self.buildlogs_path("%s-%s.txt" %
|
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)
|
tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile)
|
||||||
|
|
||||||
prettyname = "%s (%s)" % (name, desc)
|
prettyname = "%s (%s)" % (name, desc)
|
||||||
|
@ -1735,9 +1754,58 @@ class AutoTest(ABC):
|
||||||
exit(1)
|
exit(1)
|
||||||
self.progress("PASSED: Check for syntax mistake in autotest lambda")
|
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."""
|
"""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):
|
def poll_home_position(self, quiet=False):
|
||||||
|
|
|
@ -13,87 +13,35 @@ import operator
|
||||||
|
|
||||||
# get location of scripts
|
# get location of scripts
|
||||||
testdir = os.path.dirname(os.path.realpath(__file__))
|
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'
|
MISSION = 'ArduPlane-Missions/Dalby-OBC2016.txt'
|
||||||
FENCE = 'ArduPlane-Missions/Dalby-OBC2016-fence.txt'
|
FENCE = 'ArduPlane-Missions/Dalby-OBC2016-fence.txt'
|
||||||
WIND = "0,180,0.2" # speed,direction,variance
|
WIND = "0,180,0.2" # speed,direction,variance
|
||||||
|
|
||||||
|
|
||||||
class AutoTestQuadPlane(AutoTest):
|
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,
|
def default_frame(self):
|
||||||
HOME.lng,
|
return "quadplane"
|
||||||
HOME.alt,
|
|
||||||
HOME.heading)
|
|
||||||
self.homeloc = None
|
|
||||||
self.speedup = speedup
|
|
||||||
|
|
||||||
self.log_name = "QuadPlane"
|
def test_filepath(self):
|
||||||
self.logfile = None
|
return os.path.realpath(__file__)
|
||||||
|
|
||||||
self.sitl = None
|
def sitl_start_location(self):
|
||||||
|
return SITL_START_LOCATION
|
||||||
|
|
||||||
def init(self):
|
def log_name(self):
|
||||||
super(AutoTestQuadPlane, self).init(os.path.realpath(__file__))
|
return "QuadPlane"
|
||||||
if self.frame is None:
|
|
||||||
self.frame = '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()
|
vinfo = vehicleinfo.VehicleInfo()
|
||||||
defaults_file = vinfo.options["ArduPlane"]["frames"][self.frame]["default_params_filename"]
|
defaults_file = vinfo.options["ArduPlane"]["frames"][self.frame]["default_params_filename"]
|
||||||
defaults_filepath = os.path.join(testdir, defaults_file)
|
return 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!")
|
|
||||||
|
|
||||||
def is_plane(self):
|
def is_plane(self):
|
||||||
return True
|
return True
|
||||||
|
|
Loading…
Reference in New Issue