autotest: always sleep for 3 seconds on starting SITL

This commit is contained in:
Andrew Tridgell 2016-01-11 09:31:13 +11:00
parent decb6dbab0
commit 6e418c2cf5
1 changed files with 3 additions and 4 deletions

View File

@ -136,10 +136,9 @@ def start_SIL(atype, valgrind=False, gdb=False, wipe=False, synthetic_clock=True
ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5)
ret.delaybeforesend = 0
pexpect_autoclose(ret)
if gdb:
time.sleep(3)
else:
ret.expect('Waiting for connection',timeout=300)
# give time for parameters to properly setup
time.sleep(3)
ret.expect('Waiting for connection',timeout=300)
return ret
def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:5760',