autotest: Test when invalid tag is selected via DO_JUMP_TAG

This commit is contained in:
Nick Exton 2023-10-09 11:08:30 +11:00 committed by Andrew Tridgell
parent b96acbc97e
commit 64e6a85e4b

View File

@ -3275,6 +3275,22 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
timeout=1, timeout=1,
want_result=mavutil.mavlink.MAV_RESULT_DENIED) want_result=mavutil.mavlink.MAV_RESULT_DENIED)
def InvalidJumpTags(self):
'''Verify the behaviour when selecting invalid jump tags.'''
MAX_TAG_NUM = 65535
# Jump tag is not present, so expect FAILED
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
p1=MAX_TAG_NUM,
timeout=1,
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
# Jump tag is too big, so expect DENIED
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
p1=MAX_TAG_NUM+1,
timeout=1,
want_result=mavutil.mavlink.MAV_RESULT_DENIED)
def GPSViconSwitching(self): def GPSViconSwitching(self):
"""Fly GPS and Vicon switching test""" """Fly GPS and Vicon switching test"""
self.customise_SITL_commandline(["--uartF=sim:vicon:"]) self.customise_SITL_commandline(["--uartF=sim:vicon:"])
@ -10595,6 +10611,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.FlyMissionTwice, self.FlyMissionTwice,
self.FlyMissionTwiceWithReset, self.FlyMissionTwiceWithReset,
self.MissionIndexValidity, self.MissionIndexValidity,
self.InvalidJumpTags,
self.IMUConsistency, self.IMUConsistency,
self.AHRSTrimLand, self.AHRSTrimLand,
self.GuidedYawRate, self.GuidedYawRate,