From d9d9745c1118e46cab20f280c13642795ebefc03 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 18 Jan 2019 11:58:18 +1100 Subject: [PATCH] Tools: autotest: add test for QuadPlane QAutoTune --- Tools/autotest/autotest.py | 1 + Tools/autotest/quadplane.py | 33 +++++++++++++++++++++++++++++++++ 2 files changed, 34 insertions(+) diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index b36b3c8b43..32dcd55ee3 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -302,6 +302,7 @@ def run_specific_test(step, *args, **kwargs): tester_class_map = { "fly.ArduCopter": arducopter.AutoTestCopter, "fly.ArduPlane": arduplane.AutoTestPlane, + "fly.QuadPlane": quadplane.AutoTestQuadPlane, "drive.APMrover2": apmrover2.AutoTestRover, "drive.BalanceBot": balancebot.AutoTestBalanceBot, "fly.CopterAVC": arducopter.AutoTestHeli, diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 64e665bdb2..9b0a2d5a48 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -133,6 +133,37 @@ class AutoTestQuadPlane(AutoTest): self.mav.motors_disarmed_wait() self.progress("Mission OK") + def fly_qautotune(self): + self.change_mode("QHOVER") + self.wait_ready_to_arm() + self.arm_vehicle() + self.set_rc(3, 1800) + self.wait_altitude(30, + 40, + relative=True, + timeout=30) + self.set_rc(3, 1500) + self.change_mode("QAUTOTUNE") + tstart = self.get_sim_time() + sim_time_expected = 5000 + deadline = tstart + sim_time_expected + while self.get_sim_time_cached() < deadline: + now = self.get_sim_time_cached() + m = self.mav.recv_match(type='STATUSTEXT', + blocking=True, + timeout=1) + if m is None: + continue + self.progress("STATUSTEXT (%u<%u): %s" % (now, deadline, m.text)) + if "AutoTune: Success" in m.text: + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + # near enough for now: + self.change_mode("QLAND") + self.mavproxy.expect("AutoTune: Saved gains for Roll Pitch Yaw") + self.mav.motors_disarmed_wait() + return + self.mav.motors_disarmed_wait() + def default_mode(self): return "FBWA" @@ -146,6 +177,8 @@ class AutoTestQuadPlane(AutoTest): ret.extend([ ("ArmFeatures", "Arm features", self.test_arm_feature), + ("QAutoTune", "Fly QAUTOTUNE mode", self.fly_qautotune), + ("Mission", "Dalby Mission", lambda: self.fly_mission(m, f)) ])