diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 46ee64c6f6df9c..4038e1b5ca728c 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -3274,6 +3274,22 @@ def MissionIndexValidity(self): timeout=1, 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): """Fly GPS and Vicon switching test""" self.customise_SITL_commandline(["--uartF=sim:vicon:"]) @@ -10452,6 +10468,7 @@ def tests2b(self): # this block currently around 9.5mins here self.FlyMissionTwice, self.FlyMissionTwiceWithReset, self.MissionIndexValidity, + self.InvalidJumpTags, self.IMUConsistency, self.AHRSTrimLand, self.GuidedYawRate,