mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: Add test for handling of param2 (reset) of DO_SET_MISSION_CURRENT
This commit is contained in:
parent
59c5092810
commit
e2e05af914
@ -3226,6 +3226,30 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.wait_disarmed()
|
||||
self.delay_sim_time(20)
|
||||
|
||||
def FlyMissionTwiceWithReset(self):
|
||||
'''Fly a mission twice in a row without changing modes in between.
|
||||
Allow the mission to complete, then reset the mission state machine and restart the mission.'''
|
||||
|
||||
self.upload_simple_relhome_mission([
|
||||
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 20),
|
||||
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),
|
||||
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
|
||||
])
|
||||
|
||||
num_wp = self.get_mission_count()
|
||||
self.set_parameter("AUTO_OPTIONS", 3)
|
||||
self.change_mode('AUTO')
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
for i in 1, 2:
|
||||
self.progress("run %u" % i)
|
||||
# Use the "Reset Mission" param of DO_SET_MISSION_CURRENT to reset mission state machine
|
||||
self.set_current_waypoint_using_mav_cmd_do_set_mission_current(seq=0, reset=1)
|
||||
self.arm_vehicle()
|
||||
self.wait_waypoint(num_wp-1, num_wp-1)
|
||||
self.wait_disarmed()
|
||||
self.delay_sim_time(20)
|
||||
|
||||
def GPSViconSwitching(self):
|
||||
"""Fly GPS and Vicon switching test"""
|
||||
self.customise_SITL_commandline(["--uartF=sim:vicon:"])
|
||||
@ -10544,6 +10568,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.ThrottleGainBoost,
|
||||
self.ScriptMountPOI,
|
||||
self.FlyMissionTwice,
|
||||
self.FlyMissionTwiceWithReset,
|
||||
self.IMUConsistency,
|
||||
self.AHRSTrimLand,
|
||||
self.GuidedYawRate,
|
||||
|
@ -5911,10 +5911,12 @@ class TestSuite(ABC):
|
||||
def set_current_waypoint_using_mav_cmd_do_set_mission_current(
|
||||
self,
|
||||
seq,
|
||||
reset=0,
|
||||
target_sysid=1,
|
||||
target_compid=1):
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,
|
||||
p1=seq,
|
||||
p2=reset,
|
||||
timeout=1,
|
||||
target_sysid=target_sysid,
|
||||
target_compid=target_compid)
|
||||
|
Loading…
Reference in New Issue
Block a user