From 90c4b7bc271e0aff4b7d0a43f210bba15b3cce1d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 4 Sep 2024 22:25:12 +1000 Subject: [PATCH] autotest: add test for arming in guided with non-zero throttle --- Tools/autotest/arducopter.py | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index e970300da682a3..2451561af42de2 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -11840,6 +11840,23 @@ def MAV_CMD_MISSION_START_p1_p2(self): want_result=mavutil.mavlink.MAV_RESULT_DENIED, ) + def GUIDEDArmingCheckThrottle(self): + '''check the way throttle is handled when arming in guided mode''' + self.change_mode('GUIDED') + self.wait_ready_to_arm() + self.start_subtest("With zero throttle should be able to arm") + self.arm_vehicle() + self.disarm_vehicle() + + self.start_subtest("Without option set we should be able to arm with non-zero throttle in guided") + self.set_rc(3, 1600) + self.arm_vehicle() + self.disarm_vehicle() + + self.start_subtest("With option enabled should not be able to arm with non-zero throttle") + self.set_parameter("GUID_OPTIONS", 1 << 8) + self.assert_arm_failure("is not neutral") + def tests2b(self): # this block currently around 9.5mins here '''return list of all tests''' ret = ([ @@ -11941,6 +11958,7 @@ def tests2b(self): # this block currently around 9.5mins here self.MissionRTLYawBehaviour, self.BatteryInternalUseOnly, self.MAV_CMD_MISSION_START_p1_p2, + self.GUIDEDArmingCheckThrottle, ]) return ret