mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
autotest: add test for flying mission twice back-to-back
This commit is contained in:
parent
ab6886f056
commit
357a39adba
@ -3097,6 +3097,27 @@ class AutoTestCopter(AutoTest):
|
||||
if not self.current_onboard_log_contains_message("XKFD"):
|
||||
raise NotAchievedException("Did not find expected XKFD message")
|
||||
|
||||
def FlyMissionTwice(self):
|
||||
'''fly a mission twice in a row without changing modes in between.
|
||||
Seeks to show bugs in mission state machine'''
|
||||
|
||||
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)
|
||||
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:"])
|
||||
@ -9651,6 +9672,7 @@ class AutoTestCopter(AutoTest):
|
||||
self.TerrainDBPreArm,
|
||||
self.ThrottleGainBoost,
|
||||
self.ScriptMountPOI,
|
||||
self.FlyMissionTwice,
|
||||
])
|
||||
return ret
|
||||
|
||||
@ -9678,6 +9700,7 @@ class AutoTestCopter(AutoTest):
|
||||
"AltEstimation": "See https://github.com/ArduPilot/ardupilot/issues/15191",
|
||||
"GroundEffectCompensation_takeOffExpected": "Flapping",
|
||||
"GroundEffectCompensation_touchDownExpected": "Flapping",
|
||||
"FlyMissionTwice": "See https://github.com/ArduPilot/ardupilot/pull/18561",
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user