mirror of https://github.com/ArduPilot/ardupilot
autotest: fixed rover mission completion
This commit is contained in:
parent
4a02af088b
commit
5f8c8e87a8
|
@ -63,7 +63,7 @@ def drive_mission(mavproxy, mav, filename):
|
|||
wait_mode(mav, 'AUTO')
|
||||
if not wait_waypoint(mav, 1, 4, max_dist=5):
|
||||
return False
|
||||
wait_mode(mav, 'MANUAL')
|
||||
wait_mode(mav, 'HOLD')
|
||||
print("Mission OK")
|
||||
return True
|
||||
|
||||
|
|
Loading…
Reference in New Issue