From b47b97a981f45489cb6678c1c715a465080c73ec Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 5 Mar 2019 14:52:24 +1100 Subject: [PATCH] Tools: autotest: add test for QuadPlane controller pre-arm checks --- Tools/autotest/arducopter.py | 26 +------------------------- Tools/autotest/common.py | 27 +++++++++++++++++++++++++++ Tools/autotest/quadplane.py | 7 +++++++ 3 files changed, 35 insertions(+), 25 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 1239f889ff..23f6b95e75 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -2786,31 +2786,7 @@ class AutoTestCopter(AutoTest): super(AutoTestCopter, self).test_arm_feature() def test_parameter_checks(self): - self.wait_ready_to_arm() - self.context_push() - self.set_parameter("PSC_POSXY_P", -1) - self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, - 1, # ARM - 0, - 0, - 0, - 0, - 0, - 0, - timeout=2, - want_result=mavutil.mavlink.MAV_RESULT_FAILED) - self.context_pop() - self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, - 1, # ARM - 0, - 0, - 0, - 0, - 0, - 0, - timeout=2, - want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) - self.disarm_vehicle() + self.test_parameter_checks_poscontrol("PSC") def initial_mode(self): return "STABILIZE" diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 2c485e2473..7e58acd48a 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -2330,6 +2330,33 @@ switch value''' def disabled_tests(self): return {} + def test_parameter_checks_poscontrol(self, param_prefix): + self.wait_ready_to_arm() + self.context_push() + self.set_parameter("%s_POSXY_P" % param_prefix, -1) + self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, + 1, # ARM + 0, + 0, + 0, + 0, + 0, + 0, + timeout=2, + want_result=mavutil.mavlink.MAV_RESULT_FAILED) + self.context_pop() + self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, + 1, # ARM + 0, + 0, + 0, + 0, + 0, + 0, + timeout=2, + want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) + self.disarm_vehicle() + 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=5) diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 401080e254..f4ab46663a 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -192,6 +192,9 @@ class AutoTestQuadPlane(AutoTest): self.change_mode("FBWA") # we don't update PIDs in MANUAL super(AutoTestQuadPlane, self).test_pid_tuning() + def test_parameter_checks(self): + self.test_parameter_checks_poscontrol("Q_P") + def default_mode(self): return "MANUAL" @@ -212,6 +215,10 @@ class AutoTestQuadPlane(AutoTest): ("QAutoTune", "Fly QAUTOTUNE mode", self.fly_qautotune), + ("ParameterChecks", + "Test Arming Parameter Checks", + self.test_parameter_checks), + ("Mission", "Dalby Mission", lambda: self.fly_mission(m, f)) ])