mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 08:44:08 -04:00
autotest: Add timeout to fly_mission.
This commit is contained in:
parent
bde9ce10e3
commit
c3f039a739
@ -512,14 +512,14 @@ class AutoTestPlane(AutoTest):
|
|||||||
|
|
||||||
return self.wait_level_flight()
|
return self.wait_level_flight()
|
||||||
|
|
||||||
def fly_mission(self, filename):
|
def fly_mission(self, filename, mission_timeout=60.0):
|
||||||
"""Fly a mission from a file."""
|
"""Fly a mission from a file."""
|
||||||
self.progress("Flying mission %s" % filename)
|
self.progress("Flying mission %s" % filename)
|
||||||
self.load_mission(filename)
|
self.load_mission(filename)
|
||||||
self.mavproxy.send('switch 1\n') # auto mode
|
self.mavproxy.send('switch 1\n') # auto mode
|
||||||
self.wait_mode('AUTO')
|
self.wait_mode('AUTO')
|
||||||
self.wait_waypoint(1, 7, max_dist=60)
|
self.wait_waypoint(1, 7, max_dist=60)
|
||||||
self.wait_groundspeed(0, 0.5, timeout=60)
|
self.wait_groundspeed(0, 0.5, timeout=mission_timeout)
|
||||||
self.mavproxy.expect("Auto disarmed")
|
self.mavproxy.expect("Auto disarmed")
|
||||||
self.progress("Mission OK")
|
self.progress("Mission OK")
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user