From 8c35ddc0ebea520b164237b8dd5d4e738ad1a2a8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 1 Mar 2019 10:04:23 +1100 Subject: [PATCH] Tools: autotest: add PID_TUNING test --- Tools/autotest/arduplane.py | 4 ++++ Tools/autotest/common.py | 15 +++++++++++++++ Tools/autotest/quadplane.py | 4 ++++ 3 files changed, 23 insertions(+) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 4efa18dffe..ac77b35f77 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -870,6 +870,10 @@ class AutoTestPlane(AutoTest): def default_mode(self): return "MANUAL" + def test_pid_tuning(self): + self.change_mode("FBWA") # we don't update PIDs in MANUAL + super(AutoTestPlane, self).test_pid_tuning() + def tests(self): '''return list of all tests''' ret = super(AutoTestPlane, self).tests() diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index bc38a1f631..b3b8ed519c 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -2265,8 +2265,23 @@ switch value''' def disabled_tests(self): return {} + def test_pid_tuning(self): + self.progress("making sure we're not getting PID_TUNING messages") + m = self.mav.recv_match(type='PID_TUNING', blocking=True, timeout=1) + if m is not None: + raise PreconditionFailedException("Receiving PID_TUNING already") + self.set_parameter("GCS_PID_MASK", 1) + self.progress("making sure we are now getting PID_TUNING messages") + m = self.mav.recv_match(type='PID_TUNING', blocking=True, timeout=1) + if m is None: + raise PreconditionFailedException("Did not start to get PID_TUNING message") + def tests(self): return [ + ("PIDTuning", + "Test PID Tuning", + self.test_pid_tuning), + ("ArmFeatures", "Arm features", self.test_arm_feature), ("SetHome", diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index e165a319e3..b2f91ca9f6 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -186,6 +186,10 @@ class AutoTestQuadPlane(AutoTest): return self.mav.motors_disarmed_wait() + def test_pid_tuning(self): + self.change_mode("FBWA") # we don't update PIDs in MANUAL + super(AutoTestQuadPlane, self).test_pid_tuning() + def default_mode(self): return "MANUAL"