Tools: autotest: convert ArduSub over to new tests framework

This commit is contained in:
Peter Barker 2018-12-15 21:37:17 +11:00 committed by Andrew Tridgell
parent 7aa1d51585
commit 36ad5d44bd

View File

@ -49,10 +49,15 @@ class AutoTestSub(AutoTest):
self.log_name = "ArduSub"
def default_mode(self):
return 'MANUAL'
def init(self):
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.home,
@ -85,9 +90,15 @@ class AutoTestSub(AutoTest):
self.apply_defaultfile_parameters()
# FIXME:
self.set_parameter("FS_GCS_ENABLE", 0)
self.progress("Ready to start testing!")
def dive_manual(self):
self.wait_ready_to_arm()
self.arm_vehicle()
self.set_rc(3, 1600)
self.set_rc(5, 1600)
self.set_rc(6, 1550)
@ -162,53 +173,27 @@ class AutoTestSub(AutoTest):
pass
self.initialise_after_reboot_sitl()
def autotest(self):
"""Autotest ArduSub in SITL."""
self.check_test_syntax(test_file=os.path.realpath(__file__))
if not self.hasInit:
self.init()
def tests(self):
'''return list of all tests'''
ret = super(AutoTestSub, self).tests()
self.fail_list = []
try:
self.progress("Waiting for a heartbeat with mavlink protocol %s"
% self.mav.WIRE_PROTOCOL_VERSION)
self.wait_heartbeat()
self.set_parameter("FS_GCS_ENABLE", 0)
self.progress("Waiting for GPS fix")
self.mav.wait_gps_fix()
ret.extend([
("ArmFeatures", "Arm features", self.test_arm_feature),
# wait for EKF and GPS checks to pass
self.progress("Waiting for ready-to-arm")
self.wait_ready_to_arm()
self.run_test("Arm features", self.test_arm_feature)
self.arm_vehicle()
("DiveManual", "Dive manual", self.dive_manual),
self.homeloc = self.mav.location()
self.progress("Home location: %s" % self.homeloc)
self.set_rc_default()
("DiveMission",
"Dive mission",
lambda: self.dive_mission("sub_mission.txt")),
self.run_test("Arm vehicle", self.arm_vehicle)
("GripperMission",
"Test gripper mission items",
self.test_gripper_mission),
self.run_test("Dive manual", self.dive_manual)
("DownLoadLogs", "Download logs", lambda:
self.log_download(
self.buildlogs_path("APMrover2-log.bin"),
upload_logs=len(self.fail_list) > 0)),
])
self.run_test("Dive mission",
lambda: self.dive_mission("sub_mission.txt"))
self.run_test("Test gripper mission items",
self.test_gripper_mission)
self.run_test("Log download",
lambda: self.log_download(
self.buildlogs_path("ArduSub-log.bin"),
upload_logs=len(self.fail_list) > 0))
except pexpect.TIMEOUT:
self.progress("Failed with timeout")
self.fail_list.append("Failed with timeout")
self.close()
if len(self.fail_list):
self.progress("FAILED: %s" % self.fail_list)
return False
return True
return ret