From 69293f46f3fef203ab867c5c697759880344147d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 17 Dec 2018 17:57:16 +1100 Subject: [PATCH] Tools: autotest: convert Heli to new tests framework --- Tools/autotest/arducopter.py | 64 +++++++++++++++--------------------- Tools/autotest/autotest.py | 4 +-- 2 files changed, 28 insertions(+), 40 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index b7e21c3680..b588d3609c 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -81,13 +81,6 @@ class AutoTestCopter(AutoTest): self.mavproxy_logfile = self.open_mavproxy_logfile() - if self.frame == 'heli': - self.log_name = "HeliCopter" - self.home = "%f,%f,%u,%u" % (AVCHOME.lat, - AVCHOME.lng, - AVCHOME.alt, - AVCHOME.heading) - self.sitl = util.start_SITL(self.binary, model=self.frame, home=self.home, @@ -2559,42 +2552,37 @@ class AutoTestCopter(AutoTest): ]) return ret - def autotest_heli(self): - """Autotest Helicopter in SITL with AVC2013 mission.""" - self.frame = 'heli' - if not self.hasInit: - self.init() - self.fail_list = [] +class AutoTestHeli(AutoTestCopter): - try: - self.wait_heartbeat() - self.set_rc_default() - self.set_rc(3, 1000) - self.homeloc = self.mav.location() + def __init__(self, *args, **kwargs): - self.progress("Lowering rotor speed") - self.set_rc(8, 1000) - self.mavproxy.send('switch 6\n') # stabilize mode - self.wait_mode('STABILIZE') - self.wait_ready_to_arm() - - self.run_test("Arm features", self.test_arm_feature) + super(AutoTestHeli, self).__init__(*args, **kwargs) - self.run_test("Fly AVC mission", self.fly_avc_test) + self.log_name = "HeliCopter" + self.home = "%f,%f,%u,%u" % (AVCHOME.lat, + AVCHOME.lng, + AVCHOME.alt, + AVCHOME.heading) + self.frame = 'heli' - # mission ends with disarm so should be ok to download logs now - self.run_test("log download", - lambda: self.log_download( - self.buildlogs_path("Helicopter-log.bin"), - upload_logs=len(self.fail_list) > 0)) + def set_rc_default(self): + super(AutoTestCopter, self).set_rc_default() + self.progress("Lowering rotor speed") + self.set_rc(8, 1000) - except pexpect.TIMEOUT: - self.fail_list.append("Failed with timeout") + def tests(self): + '''return list of all tests''' + ret = super(AutoTestCopter, self).tests() + ret.extend([ + ("ArmFeatures", "Arm features", self.test_arm_feature), - self.close() + ("AVCMission", "Fly AVC mission", self.fly_avc_test), - if len(self.fail_list): - self.progress("FAILED: %s" % self.fail_list) - return False - return True + ("LogDownLoad", + "Log download", + lambda: self.log_download( + self.buildlogs_path("ArduPlane-log.bin"), + upload_logs=len(self.fail_list) > 0)) + ]) + return ret diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 357aa64785..3cf3f9ee2e 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -394,8 +394,8 @@ def run_step(step): return tester.autotest() if step == 'fly.CopterAVC': - tester = arducopter.AutoTestCopter(binary, **fly_opts) - return tester.autotest_heli() + tester = arducopter.AutoTestHeli(binary, **fly_opts) + return tester.autotest() if step == 'fly.ArduPlane': tester = arduplane.AutoTestPlane(binary, **fly_opts)