autotest: add test for mission_clear_all message

This commit is contained in:
Peter Barker 2024-08-19 17:13:00 +10:00 committed by Peter Barker
parent 54ec26a80a
commit 8e77f859e0

View File

@ -3596,8 +3596,30 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
raise e
self.reboot_sitl()
def ClearMission(self, target_system=1, target_component=1):
'''check mission clearing'''
self.start_subtest("Clear via mission_clear_all message")
self.upload_simple_relhome_mission([
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),
])
self.set_current_waypoint(3)
self.mav.mav.mission_clear_all_send(
target_system,
target_component,
mavutil.mavlink.MAV_MISSION_TYPE_MISSION
)
self.assert_current_waypoint(0)
def GCSMission(self):
'''check MAVProxy's waypoint handling of missions'''
target_system = 1
target_component = 1
mavproxy = self.start_mavproxy()
@ -3605,7 +3627,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.delay_sim_time(1)
if self.get_parameter("MIS_TOTAL") != 0:
raise NotAchievedException("Failed to clear mission")
m = self.assert_receive_message('MISSION_CURRENT', timeout=5)
m = self.assert_receive_message('MISSION_CURRENT', timeout=5, verbose=True)
if m.seq != 0:
raise NotAchievedException("Bad mission current")
self.load_mission_using_mavproxy(mavproxy, "rover-gripper-mission.txt")
@ -6830,6 +6852,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.MissionPolyEnabledPreArm,
self.OpticalFlow,
self.RCDuplicateOptionsExist,
self.ClearMission,
])
return ret