Tools: autotest: move close method up to common.py

This commit is contained in:
Peter Barker 2018-03-15 22:54:34 +11:00
parent 31ba99e58a
commit fe3b882bea
6 changed files with 31 additions and 86 deletions

View File

@ -54,6 +54,8 @@ class AutoTestRover(AutoTest):
self.sitl = None self.sitl = None
self.hasInit = False self.hasInit = False
self.log_name = "APMrover2"
def init(self): def init(self):
if self.frame is None: if self.frame is None:
self.frame = 'rover' self.frame = 'rover'
@ -131,22 +133,6 @@ class AutoTestRover(AutoTest):
self.hasInit = True self.hasInit = True
self.progress("Ready to start testing!") 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): # def reset_and_arm(self):
# """Reset RC, set to MANUAL and arm.""" # """Reset RC, set to MANUAL and arm."""
# self.mav.wait_heartbeat() # self.mav.wait_heartbeat()

View File

@ -159,20 +159,7 @@ class AutoTestCopter(AutoTest):
self.progress("Ready to start testing!") self.progress("Ready to start testing!")
def close(self): def close(self):
if self.use_map: super(AutoTestCopter, self).close()
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"))
# [2014/05/07] FC Because I'm doing a cross machine build # [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 # (source is on host, build is on guest VM) I cannot hard link

View File

@ -4,7 +4,6 @@
from __future__ import print_function from __future__ import print_function
import math import math
import os import os
import shutil
import pexpect import pexpect
from pymavlink import mavutil from pymavlink import mavutil
@ -48,6 +47,8 @@ class AutoTestPlane(AutoTest):
self.sitl = None self.sitl = None
self.hasInit = False self.hasInit = False
self.log_name = "ArduPlane"
def init(self): def init(self):
if self.frame is None: if self.frame is None:
self.frame = 'plane-elevrev' self.frame = 'plane-elevrev'
@ -101,22 +102,6 @@ class AutoTestPlane(AutoTest):
self.hasInit = True self.hasInit = True
self.progress("Ready to start testing!") 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): def takeoff(self):
"""Takeoff get to 30m altitude.""" """Takeoff get to 30m altitude."""

View File

@ -3,7 +3,6 @@
# Dive ArduSub in SITL # Dive ArduSub in SITL
from __future__ import print_function from __future__ import print_function
import os import os
import shutil
import pexpect import pexpect
from pymavlink import mavutil from pymavlink import mavutil
@ -47,6 +46,8 @@ class AutoTestSub(AutoTest):
self.sitl = None self.sitl = None
self.hasInit = False self.hasInit = False
self.log_name = "ArduSub"
def init(self): def init(self):
if self.frame is None: if self.frame is None:
self.frame = 'vectored' self.frame = 'vectored'
@ -124,22 +125,6 @@ class AutoTestSub(AutoTest):
self.hasInit = True self.hasInit = True
self.progress("Ready to start testing!") 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): def dive_manual(self):
self.set_rc(3, 1600) self.set_rc(3, 1600)
self.set_rc(5, 1600) self.set_rc(5, 1600)

View File

@ -1,15 +1,16 @@
from __future__ import print_function from __future__ import print_function
import abc
import math import math
import os
import shutil
import sys
import time import time
from pymavlink import mavwp, mavutil from pymavlink import mavwp, mavutil
from pysim import util from pysim import util
import sys
import abc
import os
# a list of pexpect objects to read while waiting for # a list of pexpect objects to read while waiting for
# messages. This keeps the output to stdout flowing # messages. This keeps the output to stdout flowing
expect_list = [] expect_list = []
@ -73,6 +74,24 @@ class AutoTest(ABC):
return ret 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 # GENERAL UTILITIES
################################################# #################################################

View File

@ -4,7 +4,6 @@
from __future__ import print_function from __future__ import print_function
import os import os
import pexpect import pexpect
import shutil
from pymavlink import mavutil from pymavlink import mavutil
from common import AutoTest from common import AutoTest
@ -44,7 +43,7 @@ class AutoTestQuadPlane(AutoTest):
self.speedup = speedup self.speedup = speedup
self.speedup_default = 10 self.speedup_default = 10
self.log_name = "ArduCopter" self.log_name = "QuadPlane"
self.logfile = None self.logfile = None
self.buildlog = None self.buildlog = None
self.copy_tlog = False self.copy_tlog = False
@ -104,22 +103,6 @@ class AutoTestQuadPlane(AutoTest):
self.hasInit = True self.hasInit = True
self.progress("Ready to start testing!") 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): # def test_arm_motors_radio(self):
# super(AutotestQuadPlane, self).test_arm_motors_radio() # super(AutotestQuadPlane, self).test_arm_motors_radio()
# #