autotest: Add test for mission containing jump that points to itself

This commit is contained in:
James O'Shannessy 2024-11-13 13:55:28 +11:00
parent 9f29606d1c
commit 0219c487e4
1 changed files with 35 additions and 0 deletions

View File

@ -6289,6 +6289,40 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
self.wait_current_waypoint(4) self.wait_current_waypoint(4)
self.fly_home_land_and_disarm() self.fly_home_land_and_disarm()
def MAV_CMD_DO_JUMP_to_self(self):
'''Test MAV_CMD_DO_JUMP to Jumping To Self and skipping rest of mission'''
offset = 500
alt = self.get_parameter("RTL_ALTITUDE")
self.upload_simple_relhome_mission([
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 10),
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, offset, offset, alt),
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, offset, -offset, alt),
self.create_MISSION_ITEM_INT(
mavutil.mavlink.MAV_CMD_DO_JUMP,
p1=4, # waypoint to jump to
p2=-1 # number of jumps (-1: infinite)
),
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, -offset, -offset, alt),
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, -offset, offset, alt)
])
self.change_mode("AUTO")
self.wait_ready_to_arm()
self.arm_vehicle()
# check the vehicle is flying to each waypoint as expected
self.wait_distance_to_waypoint(2, distance_min=10, distance_max=20, timeout=90) # North East
self.wait_distance_to_waypoint(3, distance_min=10, distance_max=20, timeout=90) # North West
self.progress("check MAV_CMD_DO_JUMP to self did not cause RTL")
self.delay_sim_time(5)
self.assert_mode_is("AUTO")
self.wait_distance_to_waypoint(5, distance_min=10, distance_max=20, timeout=90) # South West
self.wait_distance_to_waypoint(6, distance_min=10, distance_max=20, timeout=90) # South East
self.fly_home_land_and_disarm()
def tests(self): def tests(self):
'''return list of all tests''' '''return list of all tests'''
ret = [] ret = []
@ -6437,6 +6471,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
self.MAV_CMD_EXTERNAL_WIND_ESTIMATE, self.MAV_CMD_EXTERNAL_WIND_ESTIMATE,
self.GliderPullup, self.GliderPullup,
self.BadRollChannelDefined, self.BadRollChannelDefined,
self.MAV_CMD_DO_JUMP_to_self,
] ]
def disabled_tests(self): def disabled_tests(self):