From fe3b882beae15c714d90b6b92842f71eb633ed57 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 15 Mar 2018 22:54:34 +1100 Subject: [PATCH] Tools: autotest: move close method up to common.py --- Tools/autotest/apmrover2.py | 18 ++---------------- Tools/autotest/arducopter.py | 15 +-------------- Tools/autotest/arduplane.py | 19 ++----------------- Tools/autotest/ardusub.py | 19 ++----------------- Tools/autotest/common.py | 27 +++++++++++++++++++++++---- Tools/autotest/quadplane.py | 19 +------------------ 6 files changed, 31 insertions(+), 86 deletions(-) diff --git a/Tools/autotest/apmrover2.py b/Tools/autotest/apmrover2.py index 1a9b0cee7e..00c72dcf9d 100644 --- a/Tools/autotest/apmrover2.py +++ b/Tools/autotest/apmrover2.py @@ -54,6 +54,8 @@ class AutoTestRover(AutoTest): self.sitl = None self.hasInit = False + self.log_name = "APMrover2" + def init(self): if self.frame is None: self.frame = 'rover' @@ -131,22 +133,6 @@ class AutoTestRover(AutoTest): self.hasInit = True self.progress("Ready to start testing!") - def close(self): - if self.use_map: - self.mavproxy.send("module unload map\n") - self.mavproxy.expect("Unloaded module map") - - self.mav.close() - util.pexpect_close(self.mavproxy) - util.pexpect_close(self.sitl) - - valgrind_log = util.valgrind_log_filepath(binary=self.binary, - model=self.frame) - if os.path.exists(valgrind_log): - os.chmod(valgrind_log, 0o644) - shutil.copy(valgrind_log, - self.buildlogs_path("APMrover2-valgrind.log")) - # def reset_and_arm(self): # """Reset RC, set to MANUAL and arm.""" # self.mav.wait_heartbeat() diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 37396b5493..c79dccc732 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -159,20 +159,7 @@ class AutoTestCopter(AutoTest): self.progress("Ready to start testing!") def close(self): - if self.use_map: - self.mavproxy.send("module unload map\n") - self.mavproxy.expect("Unloaded module map") - - self.mav.close() - util.pexpect_close(self.mavproxy) - util.pexpect_close(self.sitl) - - valgrind_log = util.valgrind_log_filepath(binary=self.binary, - model=self.frame) - if os.path.exists(valgrind_log): - os.chmod(valgrind_log, 0o644) - shutil.copy(valgrind_log, - self.buildlogs_path(self.log_name + "-valgrind.log")) + super(AutoTestCopter, self).close() # [2014/05/07] FC Because I'm doing a cross machine build # (source is on host, build is on guest VM) I cannot hard link diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 8c27adf606..3f03ba96ca 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -4,7 +4,6 @@ from __future__ import print_function import math import os -import shutil import pexpect from pymavlink import mavutil @@ -48,6 +47,8 @@ class AutoTestPlane(AutoTest): self.sitl = None self.hasInit = False + self.log_name = "ArduPlane" + def init(self): if self.frame is None: self.frame = 'plane-elevrev' @@ -101,22 +102,6 @@ class AutoTestPlane(AutoTest): self.hasInit = True self.progress("Ready to start testing!") - def close(self): - if self.use_map: - self.mavproxy.send("module unload map\n") - self.mavproxy.expect("Unloaded module map") - - self.mav.close() - util.pexpect_close(self.mavproxy) - util.pexpect_close(self.sitl) - - valgrind_log = util.valgrind_log_filepath(binary=self.binary, - model=self.frame) - if os.path.exists(valgrind_log): - os.chmod(valgrind_log, 0o644) - shutil.copy(valgrind_log, - self.buildlogs_path("ArduPlane-valgrind.log")) - def takeoff(self): """Takeoff get to 30m altitude.""" diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index 5a7ce884d9..d459924b21 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -3,7 +3,6 @@ # Dive ArduSub in SITL from __future__ import print_function import os -import shutil import pexpect from pymavlink import mavutil @@ -47,6 +46,8 @@ class AutoTestSub(AutoTest): self.sitl = None self.hasInit = False + self.log_name = "ArduSub" + def init(self): if self.frame is None: self.frame = 'vectored' @@ -124,22 +125,6 @@ class AutoTestSub(AutoTest): self.hasInit = True self.progress("Ready to start testing!") - def close(self): - if self.use_map: - self.mavproxy.send("module unload map\n") - self.mavproxy.expect("Unloaded module map") - - self.mav.close() - util.pexpect_close(self.mavproxy) - util.pexpect_close(self.sitl) - - valgrind_log = util.valgrind_log_filepath(binary=self.binary, - model=self.frame) - if os.path.exists(valgrind_log): - os.chmod(valgrind_log, 0o644) - shutil.copy(valgrind_log, - self.buildlogs_path("ArduSub-valgrind.log")) - def dive_manual(self): self.set_rc(3, 1600) self.set_rc(5, 1600) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index c99683a62a..bbb8d7b1ee 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -1,15 +1,16 @@ from __future__ import print_function + +import abc import math +import os +import shutil +import sys import time from pymavlink import mavwp, mavutil from pysim import util -import sys -import abc -import os - # a list of pexpect objects to read while waiting for # messages. This keeps the output to stdout flowing expect_list = [] @@ -73,6 +74,24 @@ class AutoTest(ABC): return ret + def close(self): + '''tidy up after running all tests''' + if self.use_map: + self.mavproxy.send("module unload map\n") + self.mavproxy.expect("Unloaded module map") + + self.mav.close() + util.pexpect_close(self.mavproxy) + util.pexpect_close(self.sitl) + + valgrind_log = util.valgrind_log_filepath(binary=self.binary, + model=self.frame) + if os.path.exists(valgrind_log): + os.chmod(valgrind_log, 0o644) + shutil.copy(valgrind_log, + self.buildlogs_path("%s-valgrind.log" % + self.log_name)) + ################################################# # GENERAL UTILITIES ################################################# diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 7f35672eaa..93fc63acc1 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -4,7 +4,6 @@ from __future__ import print_function import os import pexpect -import shutil from pymavlink import mavutil from common import AutoTest @@ -44,7 +43,7 @@ class AutoTestQuadPlane(AutoTest): self.speedup = speedup self.speedup_default = 10 - self.log_name = "ArduCopter" + self.log_name = "QuadPlane" self.logfile = None self.buildlog = None self.copy_tlog = False @@ -104,22 +103,6 @@ class AutoTestQuadPlane(AutoTest): self.hasInit = True self.progress("Ready to start testing!") - def close(self): - if self.use_map: - self.mavproxy.send("module unload map\n") - self.mavproxy.expect("Unloaded module map") - - self.mav.close() - util.pexpect_close(self.mavproxy) - util.pexpect_close(self.sitl) - - valgrind_log = util.valgrind_log_filepath(binary=self.binary, - model=self.frame) - if os.path.exists(valgrind_log): - os.chmod(valgrind_log, 0o644) - shutil.copy(valgrind_log, - self.buildlogs_path("QuadPlane-valgrind.log")) - # def test_arm_motors_radio(self): # super(AutotestQuadPlane, self).test_arm_motors_radio() #