Skip to content

Commit

Permalink
autotest: add test for arming in guided with non-zero throttle
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Sep 4, 2024
1 parent 132ec1b commit 90c4b7b
Showing 1 changed file with 18 additions and 0 deletions.
18 changes: 18 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -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 = ([
Expand Down Expand Up @@ -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

Expand Down

0 comments on commit 90c4b7b

Please sign in to comment.