From 8511c2c04b1a93f7508b5a425551d420dbaae94a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 16 Mar 2018 09:56:37 +1100 Subject: [PATCH] Tools: autotest: factor out apply_parameters_using_sitl Three of our models start a SITL instance to apply parameters then restart it so that the parameter changes can take effect. Factor that functionality out. --- Tools/autotest/apmrover2.py | 29 +---------------------------- Tools/autotest/arducopter.py | 32 ++++---------------------------- Tools/autotest/ardusub.py | 29 +---------------------------- Tools/autotest/common.py | 36 ++++++++++++++++++++++++++++++++++-- 4 files changed, 40 insertions(+), 86 deletions(-) diff --git a/Tools/autotest/apmrover2.py b/Tools/autotest/apmrover2.py index 00c72dcf9d..36d53d9f81 100644 --- a/Tools/autotest/apmrover2.py +++ b/Tools/autotest/apmrover2.py @@ -11,7 +11,6 @@ import time from common import AutoTest from pysim import util -from pysim import vehicleinfo from pymavlink import mavutil @@ -60,33 +59,7 @@ class AutoTestRover(AutoTest): if self.frame is None: self.frame = 'rover' - self.sitl = util.start_SITL(self.binary, - wipe=True, - model=self.frame, - home=self.home, - speedup=self.speedup_default) - self.mavproxy = util.start_MAVProxy_SITL('APMrover2') - - self.progress("WAITING FOR PARAMETERS") - self.mavproxy.expect('Received [0-9]+ parameters') - - # setup test parameters - vinfo = vehicleinfo.VehicleInfo() - if self.params is None: - frames = vinfo.options["APMrover2"]["frames"] - self.params = frames[self.frame]["default_params_filename"] - if not isinstance(self.params, list): - self.params = [self.params] - for x in self.params: - self.mavproxy.send("param load %s\n" % os.path.join(testdir, x)) - self.mavproxy.expect('Loaded [0-9]+ parameters') - self.set_parameter('LOG_REPLAY', 1) - self.set_parameter('LOG_DISARMED', 1) - self.progress("RELOADING SITL WITH NEW PARAMETERS") - - # restart with new parms - util.pexpect_close(self.mavproxy) - util.pexpect_close(self.sitl) + self.apply_parameters_using_sitl() self.sitl = util.start_SITL(self.binary, model=self.frame, diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index c79dccc732..d69042dd78 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -10,7 +10,6 @@ import pexpect from pymavlink import mavutil from pysim import util -from pysim import vehicleinfo from common import AutoTest @@ -70,6 +69,9 @@ class AutoTestCopter(AutoTest): def sitl_streamrate(self): return 5 + def vehicleinfo_key(self): + return 'ArduCopter' + def init(self): if self.frame is None: self.frame = '+' @@ -81,33 +83,7 @@ class AutoTestCopter(AutoTest): AVCHOME.alt, AVCHOME.heading) - self.sitl = util.start_SITL(self.binary, - wipe=True, - model=self.frame, - home=self.home, - speedup=self.speedup_default) - self.mavproxy = util.start_MAVProxy_SITL('ArduCopter') - - self.progress("WAITING FOR PARAMETERS") - self.mavproxy.expect('Received [0-9]+ parameters') - - # setup test parameters - vinfo = vehicleinfo.VehicleInfo() - if self.params is None: - frames = vinfo.options["ArduCopter"]["frames"] - self.params = frames[self.frame]["default_params_filename"] - if not isinstance(self.params, list): - self.params = [self.params] - for x in self.params: - self.mavproxy.send("param load %s\n" % os.path.join(testdir, x)) - self.mavproxy.expect('Loaded [0-9]+ parameters') - self.set_parameter('LOG_REPLAY', 1) - self.set_parameter('LOG_DISARMED', 1) - self.progress("RELOADING SITL WITH NEW PARAMETERS") - - # restart with new parms - util.pexpect_close(self.mavproxy) - util.pexpect_close(self.sitl) + self.apply_parameters_using_sitl() self.sitl = util.start_SITL(self.binary, model=self.frame, diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index d459924b21..755f078381 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -8,7 +8,6 @@ import pexpect from pymavlink import mavutil from pysim import util -from pysim import vehicleinfo from common import AutoTest @@ -52,33 +51,7 @@ class AutoTestSub(AutoTest): if self.frame is None: self.frame = 'vectored' - self.sitl = util.start_SITL(self.binary, - wipe=True, - model=self.frame, - home=self.home, - speedup=self.speedup_default) - self.mavproxy = util.start_MAVProxy_SITL('ArduSub') - - self.progress("WAITING FOR PARAMETERS") - self.mavproxy.expect('Received [0-9]+ parameters') - - # setup test parameters - vinfo = vehicleinfo.VehicleInfo() - if self.params is None: - frames = vinfo.options["ArduSub"]["frames"] - self.params = frames[self.frame]["default_params_filename"] - if not isinstance(self.params, list): - self.params = [self.params] - for x in self.params: - self.mavproxy.send("param load %s\n" % os.path.join(testdir, x)) - self.mavproxy.expect('Loaded [0-9]+ parameters') - self.set_parameter('LOG_REPLAY', 1) - self.set_parameter('LOG_DISARMED', 1) - self.progress("RELOADING SITL WITH NEW PARAMETERS") - - # restart with new parms - util.pexpect_close(self.mavproxy) - util.pexpect_close(self.sitl) + self.apply_parameters_using_sitl() self.sitl = util.start_SITL(self.binary, model=self.frame, diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index bbb8d7b1ee..a9b3d53a2a 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -8,8 +8,7 @@ import sys import time from pymavlink import mavwp, mavutil - -from pysim import util +from pysim import util, vehicleinfo # a list of pexpect objects to read while waiting for # messages. This keeps the output to stdout flowing @@ -74,6 +73,39 @@ class AutoTest(ABC): return ret + def vehicleinfo_key(self): + return self.log_name + + def apply_parameters_using_sitl(self): + '''start SITL, apply parameter file, stop SITL''' + sitl = util.start_SITL(self.binary, + wipe=True, + model=self.frame, + home=self.home, + speedup=self.speedup_default) + self.mavproxy = util.start_MAVProxy_SITL(self.log_name) + + self.progress("WAITING FOR PARAMETERS") + self.mavproxy.expect('Received [0-9]+ parameters') + + # setup test parameters + vinfo = vehicleinfo.VehicleInfo() + if self.params is None: + frames = vinfo.options[self.vehicleinfo_key()]["frames"] + self.params = frames[self.frame]["default_params_filename"] + if not isinstance(self.params, list): + self.params = [self.params] + for x in self.params: + self.mavproxy.send("param load %s\n" % os.path.join(testdir, x)) + self.mavproxy.expect('Loaded [0-9]+ parameters') + self.set_parameter('LOG_REPLAY', 1) + self.set_parameter('LOG_DISARMED', 1) + + # kill this SITL instance off: + util.pexpect_close(self.mavproxy) + util.pexpect_close(sitl) + self.mavproxy = None + def close(self): '''tidy up after running all tests''' if self.use_map: