Tools: autotest: use reboot to apply parameter changes; avoid sim restart

Previously we stopped the simulation to ensure parameter changes are
applied to the simulated vehicle.  We can now reboot the simulated
autopilot, so these patches make use of those changes.

One big advantage is that the --gdb option is in play for the applying
of the parameters to the vehicle.
This commit is contained in:
Peter Barker 2018-06-27 10:56:01 +10:00 committed by Peter Barker
parent b4d527a9f8
commit 975b8c2e5f
4 changed files with 24 additions and 24 deletions

View File

@ -62,15 +62,14 @@ class AutoTestRover(AutoTest):
if self.frame is None: if self.frame is None:
self.frame = 'rover' self.frame = 'rover'
self.apply_parameters_using_sitl()
self.sitl = util.start_SITL(self.binary, self.sitl = util.start_SITL(self.binary,
model=self.frame, model=self.frame,
home=self.home, home=self.home,
speedup=self.speedup, speedup=self.speedup,
valgrind=self.valgrind, valgrind=self.valgrind,
gdb=self.gdb, gdb=self.gdb,
gdbserver=self.gdbserver) gdbserver=self.gdbserver,
wipe=True)
self.mavproxy = util.start_MAVProxy_SITL( self.mavproxy = util.start_MAVProxy_SITL(
'APMrover2', options=self.mavproxy_options()) 'APMrover2', options=self.mavproxy_options())
self.mavproxy.expect('Telemetry log: (\S+)\r\n') self.mavproxy.expect('Telemetry log: (\S+)\r\n')
@ -86,6 +85,7 @@ class AutoTestRover(AutoTest):
except Exception: except Exception:
pass pass
self.progress("WAITING FOR PARAMETERS")
self.mavproxy.expect('Received [0-9]+ parameters') self.mavproxy.expect('Received [0-9]+ parameters')
util.expect_setup_callback(self.mavproxy, self.expect_callback) util.expect_setup_callback(self.mavproxy, self.expect_callback)
@ -107,6 +107,9 @@ class AutoTestRover(AutoTest):
self.mav.message_hooks.append(self.message_hook) self.mav.message_hooks.append(self.message_hook)
self.mav.idle_hooks.append(self.idle_hook) self.mav.idle_hooks.append(self.idle_hook)
self.hasInit = True self.hasInit = True
self.apply_defaultfile_parameters()
self.progress("Ready to start testing!") self.progress("Ready to start testing!")
# def reset_and_arm(self): # def reset_and_arm(self):

View File

@ -84,17 +84,17 @@ class AutoTestCopter(AutoTest):
AVCHOME.alt, AVCHOME.alt,
AVCHOME.heading) AVCHOME.heading)
self.apply_parameters_using_sitl()
self.sitl = util.start_SITL(self.binary, self.sitl = util.start_SITL(self.binary,
model=self.frame, model=self.frame,
home=self.home, home=self.home,
speedup=self.speedup, speedup=self.speedup,
valgrind=self.valgrind, valgrind=self.valgrind,
gdb=self.gdb, gdb=self.gdb,
gdbserver=self.gdbserver) gdbserver=self.gdbserver,
wipe=True)
self.mavproxy = util.start_MAVProxy_SITL( self.mavproxy = util.start_MAVProxy_SITL(
'ArduCopter', options=self.mavproxy_options()) 'ArduCopter', options=self.mavproxy_options())
self.mavproxy.expect('Telemetry log: (\S+)\r\n') self.mavproxy.expect('Telemetry log: (\S+)\r\n')
self.logfile = self.mavproxy.match.group(1) self.logfile = self.mavproxy.match.group(1)
self.progress("LOGFILE %s" % self.logfile) self.progress("LOGFILE %s" % self.logfile)
@ -112,8 +112,11 @@ class AutoTestCopter(AutoTest):
(self.logfile, self.buildlog)) (self.logfile, self.buildlog))
self.copy_tlog = True self.copy_tlog = True
self.progress("WAITING FOR PARAMETERS")
self.mavproxy.expect('Received [0-9]+ parameters') self.mavproxy.expect('Received [0-9]+ parameters')
self.apply_defaultfile_parameters()
util.expect_setup_callback(self.mavproxy, self.expect_callback) util.expect_setup_callback(self.mavproxy, self.expect_callback)
self.expect_list_clear() self.expect_list_clear()

View File

@ -51,15 +51,14 @@ class AutoTestSub(AutoTest):
if self.frame is None: if self.frame is None:
self.frame = 'vectored' self.frame = 'vectored'
self.apply_parameters_using_sitl()
self.sitl = util.start_SITL(self.binary, self.sitl = util.start_SITL(self.binary,
model=self.frame, model=self.frame,
home=self.home, home=self.home,
speedup=self.speedup, speedup=self.speedup,
valgrind=self.valgrind, valgrind=self.valgrind,
gdb=self.gdb, gdb=self.gdb,
gdbserver=self.gdbserver) gdbserver=self.gdbserver,
wipe=True)
self.mavproxy = util.start_MAVProxy_SITL( self.mavproxy = util.start_MAVProxy_SITL(
'ArduSub', options=self.mavproxy_options()) 'ArduSub', options=self.mavproxy_options())
self.mavproxy.expect('Telemetry log: (\S+)\r\n') self.mavproxy.expect('Telemetry log: (\S+)\r\n')
@ -75,6 +74,7 @@ class AutoTestSub(AutoTest):
except Exception: except Exception:
pass pass
self.progress("WAITING FOR PARAMETERS")
self.mavproxy.expect('Received [0-9]+ parameters') self.mavproxy.expect('Received [0-9]+ parameters')
util.expect_setup_callback(self.mavproxy, self.expect_callback) util.expect_setup_callback(self.mavproxy, self.expect_callback)
@ -96,6 +96,9 @@ class AutoTestSub(AutoTest):
self.mav.message_hooks.append(self.message_hook) self.mav.message_hooks.append(self.message_hook)
self.mav.idle_hooks.append(self.idle_hook) self.mav.idle_hooks.append(self.idle_hook)
self.hasInit = True self.hasInit = True
self.apply_defaultfile_parameters()
self.progress("Ready to start testing!") self.progress("Ready to start testing!")
def dive_manual(self): def dive_manual(self):

View File

@ -146,17 +146,8 @@ class AutoTest(ABC):
def vehicleinfo_key(self): def vehicleinfo_key(self):
return self.log_name return self.log_name
def apply_parameters_using_sitl(self): def apply_defaultfile_parameters(self):
'''start SITL, apply parameter file, stop SITL''' '''apply parameter file'''
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 # setup test parameters
vinfo = vehicleinfo.VehicleInfo() vinfo = vehicleinfo.VehicleInfo()
@ -170,11 +161,11 @@ class AutoTest(ABC):
self.mavproxy.expect('Loaded [0-9]+ parameters') self.mavproxy.expect('Loaded [0-9]+ parameters')
self.set_parameter('LOG_REPLAY', 1) self.set_parameter('LOG_REPLAY', 1)
self.set_parameter('LOG_DISARMED', 1) self.set_parameter('LOG_DISARMED', 1)
self.reboot_sitl()
# kill this SITL instance off: def reboot_sitl(self):
util.pexpect_close(self.mavproxy) self.mavproxy.send("reboot\n")
util.pexpect_close(sitl) self.mavproxy.expect("tilt alignment complete")
self.mavproxy = None
def close(self): def close(self):
'''tidy up after running all tests''' '''tidy up after running all tests'''