mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
autotest: added option of autotest with gdb
This commit is contained in:
parent
097c2011e1
commit
decb6dbab0
@ -105,12 +105,17 @@ def pexpect_drain(p):
|
|||||||
except pexpect.TIMEOUT:
|
except pexpect.TIMEOUT:
|
||||||
pass
|
pass
|
||||||
|
|
||||||
def start_SIL(atype, valgrind=False, wipe=False, synthetic_clock=True, home=None, model=None, speedup=1, defaults_file=None):
|
def start_SIL(atype, valgrind=False, gdb=False, wipe=False, synthetic_clock=True, home=None, model=None, speedup=1, defaults_file=None):
|
||||||
'''launch a SIL instance'''
|
'''launch a SIL instance'''
|
||||||
import pexpect
|
import pexpect
|
||||||
cmd=""
|
cmd=""
|
||||||
if valgrind and os.path.exists('/usr/bin/valgrind'):
|
if valgrind and os.path.exists('/usr/bin/valgrind'):
|
||||||
cmd += 'valgrind -q --log-file=%s-valgrind.log ' % atype
|
cmd += 'valgrind -q --log-file=%s-valgrind.log ' % atype
|
||||||
|
if gdb:
|
||||||
|
f = open("/tmp/x.gdb", "w")
|
||||||
|
f.write("r\n");
|
||||||
|
f.close()
|
||||||
|
cmd += 'xterm -e gdb -x /tmp/x.gdb --args '
|
||||||
executable = reltopdir('tmp/%s.build/%s.elf' % (atype, atype))
|
executable = reltopdir('tmp/%s.build/%s.elf' % (atype, atype))
|
||||||
if not os.path.exists(executable):
|
if not os.path.exists(executable):
|
||||||
executable = '/tmp/%s.build/%s.elf' % (atype, atype)
|
executable = '/tmp/%s.build/%s.elf' % (atype, atype)
|
||||||
@ -131,7 +136,10 @@ def start_SIL(atype, valgrind=False, wipe=False, synthetic_clock=True, home=None
|
|||||||
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)
|
||||||
ret.expect('Waiting for connection')
|
if gdb:
|
||||||
|
time.sleep(3)
|
||||||
|
else:
|
||||||
|
ret.expect('Waiting for connection',timeout=300)
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:5760',
|
def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:5760',
|
||||||
|
Loading…
Reference in New Issue
Block a user