mirror of https://github.com/ArduPilot/ardupilot
autotest: always sleep for 3 seconds on starting SITL
This commit is contained in:
parent
decb6dbab0
commit
6e418c2cf5
|
@ -136,9 +136,8 @@ def start_SIL(atype, valgrind=False, gdb=False, wipe=False, synthetic_clock=True
|
||||||
ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5)
|
ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5)
|
||||||
ret.delaybeforesend = 0
|
ret.delaybeforesend = 0
|
||||||
pexpect_autoclose(ret)
|
pexpect_autoclose(ret)
|
||||||
if gdb:
|
# give time for parameters to properly setup
|
||||||
time.sleep(3)
|
time.sleep(3)
|
||||||
else:
|
|
||||||
ret.expect('Waiting for connection',timeout=300)
|
ret.expect('Waiting for connection',timeout=300)
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue