mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Added more time for timeouts
This commit is contained in:
parent
d475e7ced5
commit
5ddcf3fc57
@ -135,7 +135,7 @@ def wait_location(mav, loc, accuracy=5, timeout=30, target_altitude=None, height
|
|||||||
print("Failed to attain location")
|
print("Failed to attain location")
|
||||||
return False
|
return False
|
||||||
|
|
||||||
def wait_waypoint(mav, wpnum_start, wpnum_end, allow_skip=True, timeout=60):
|
def wait_waypoint(mav, wpnum_start, wpnum_end, allow_skip=True, timeout=400):
|
||||||
'''wait for waypoint ranges'''
|
'''wait for waypoint ranges'''
|
||||||
tstart = time.time()
|
tstart = time.time()
|
||||||
# this message arrives after we set the current WP
|
# this message arrives after we set the current WP
|
||||||
|
Loading…
Reference in New Issue
Block a user