mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
autotest: add --gdb option to autotest.py
This commit is contained in:
parent
1f96336f7c
commit
b23f983459
@ -79,7 +79,7 @@ def drive_mission(mavproxy, mav, filename):
|
||||
return True
|
||||
|
||||
|
||||
def drive_APMrover2(binary, viewerip=None, map=False, valgrind=False):
|
||||
def drive_APMrover2(binary, viewerip=None, map=False, valgrind=False, gdb=False):
|
||||
'''drive APMrover2 in SIL
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
@ -111,7 +111,7 @@ def drive_APMrover2(binary, viewerip=None, map=False, valgrind=False):
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sil)
|
||||
|
||||
sil = util.start_SIL(binary, model='rover', home=home, speedup=10, valgrind=valgrind)
|
||||
sil = util.start_SIL(binary, model='rover', home=home, speedup=10, valgrind=valgrind, gdb=gdb)
|
||||
mavproxy = util.start_MAVProxy_SIL('APMrover2', options=options)
|
||||
mavproxy.expect('Telemetry log: (\S+)')
|
||||
logfile = mavproxy.match.group(1)
|
||||
|
@ -914,7 +914,7 @@ def setup_rc(mavproxy):
|
||||
# zero throttle
|
||||
mavproxy.send('rc 3 1000\n')
|
||||
|
||||
def fly_ArduCopter(binary, viewerip=None, map=False, valgrind=False):
|
||||
def fly_ArduCopter(binary, viewerip=None, map=False, valgrind=False, gdb=False):
|
||||
'''fly ArduCopter in SIL
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
@ -938,7 +938,7 @@ def fly_ArduCopter(binary, viewerip=None, map=False, valgrind=False):
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sil)
|
||||
|
||||
sil = util.start_SIL(binary, model='+', home=home, speedup=speedup_default, valgrind=valgrind)
|
||||
sil = util.start_SIL(binary, model='+', home=home, speedup=speedup_default, valgrind=valgrind, gdb=gdb)
|
||||
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5'
|
||||
if viewerip:
|
||||
options += ' --out=%s:14550' % viewerip
|
||||
@ -1265,7 +1265,7 @@ def fly_ArduCopter(binary, viewerip=None, map=False, valgrind=False):
|
||||
return True
|
||||
|
||||
|
||||
def fly_CopterAVC(binary, viewerip=None, map=False, valgrind=False):
|
||||
def fly_CopterAVC(binary, viewerip=None, map=False, valgrind=False, gdb=False):
|
||||
'''fly ArduCopter in SIL for AVC2013 mission
|
||||
'''
|
||||
global homeloc
|
||||
@ -1286,7 +1286,7 @@ def fly_CopterAVC(binary, viewerip=None, map=False, valgrind=False):
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sil)
|
||||
|
||||
sil = util.start_SIL(binary, model='heli', home=home, speedup=speedup_default, valgrind=valgrind)
|
||||
sil = util.start_SIL(binary, model='heli', home=home, speedup=speedup_default, valgrind=valgrind, gdb=gdb)
|
||||
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=5'
|
||||
if viewerip:
|
||||
options += ' --out=%s:14550' % viewerip
|
||||
|
@ -426,7 +426,7 @@ def fly_mission(mavproxy, mav, filename, height_accuracy=-1, target_altitude=Non
|
||||
return True
|
||||
|
||||
|
||||
def fly_ArduPlane(binary, viewerip=None, map=False, valgrind=False):
|
||||
def fly_ArduPlane(binary, viewerip=None, map=False, valgrind=False, gdb=False):
|
||||
'''fly ArduPlane in SIL
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
@ -461,7 +461,7 @@ def fly_ArduPlane(binary, viewerip=None, map=False, valgrind=False):
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sil)
|
||||
|
||||
sil = util.start_SIL(binary, model='jsbsim', home=HOME_LOCATION, speedup=10, valgrind=valgrind)
|
||||
sil = util.start_SIL(binary, model='jsbsim', home=HOME_LOCATION, speedup=10, valgrind=valgrind, gdb=gdb)
|
||||
mavproxy = util.start_MAVProxy_SIL('ArduPlane', options=options)
|
||||
mavproxy.expect('Telemetry log: (\S+)')
|
||||
logfile = mavproxy.match.group(1)
|
||||
|
@ -144,6 +144,7 @@ parser.add_option("--map", action='store_true', default=False, help='show map')
|
||||
parser.add_option("--experimental", default=False, action='store_true', help='enable experimental tests')
|
||||
parser.add_option("--timeout", default=3000, type='int', help='maximum runtime in seconds')
|
||||
parser.add_option("--valgrind", default=False, action='store_true', help='run ArduPilot binaries under valgrind')
|
||||
parser.add_option("--gdb", default=False, action='store_true', help='run ArduPilot binaries under gdb')
|
||||
parser.add_option("--debug", default=False, action='store_true', help='make built binaries debug binaries')
|
||||
parser.add_option("-j", default=None, type='int', help='build CPUs')
|
||||
|
||||
@ -265,19 +266,19 @@ def run_step(step):
|
||||
return get_default_params('APMrover2', binary)
|
||||
|
||||
if step == 'fly.ArduCopter':
|
||||
return arducopter.fly_ArduCopter(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
|
||||
return arducopter.fly_ArduCopter(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb)
|
||||
|
||||
if step == 'fly.CopterAVC':
|
||||
return arducopter.fly_CopterAVC(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
|
||||
return arducopter.fly_CopterAVC(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb)
|
||||
|
||||
if step == 'fly.ArduPlane':
|
||||
return arduplane.fly_ArduPlane(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
|
||||
return arduplane.fly_ArduPlane(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb)
|
||||
|
||||
if step == 'fly.QuadPlane':
|
||||
return quadplane.fly_QuadPlane(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
|
||||
return quadplane.fly_QuadPlane(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb)
|
||||
|
||||
if step == 'drive.APMrover2':
|
||||
return apmrover2.drive_APMrover2(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
|
||||
return apmrover2.drive_APMrover2(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb)
|
||||
|
||||
if step == 'build.All':
|
||||
return build_all()
|
||||
|
@ -190,7 +190,15 @@ class SIL(pexpect.spawn):
|
||||
pexpect_autoclose(self)
|
||||
# give time for parameters to properly setup
|
||||
time.sleep(3)
|
||||
self.expect('Waiting for connection',timeout=300)
|
||||
if gdb:
|
||||
# if we run GDB we do so in an xterm. "Waiting for
|
||||
# connection" is never going to appear on xterm's output.
|
||||
#... so let's give it another magic second.
|
||||
time.sleep(1)
|
||||
# TODO: have a SITL-compiled ardupilot able to have its
|
||||
# console on an output fd.
|
||||
else:
|
||||
self.expect('Waiting for connection',timeout=300)
|
||||
|
||||
|
||||
def valgrind_log_filepath(self):
|
||||
|
@ -40,7 +40,7 @@ def fly_mission(mavproxy, mav, filename, fence, height_accuracy=-1):
|
||||
return True
|
||||
|
||||
|
||||
def fly_QuadPlane(binary, viewerip=None, map=False, valgrind=False):
|
||||
def fly_QuadPlane(binary, viewerip=None, map=False, valgrind=False, gdb=False):
|
||||
'''fly QuadPlane in SIL
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
@ -55,7 +55,7 @@ def fly_QuadPlane(binary, viewerip=None, map=False, valgrind=False):
|
||||
options += ' --map'
|
||||
|
||||
sil = util.start_SIL(binary, model='quadplane', wipe=True, home=HOME_LOCATION, speedup=10,
|
||||
defaults_file=os.path.join(testdir, 'quadplane.parm'), valgrind=valgrind)
|
||||
defaults_file=os.path.join(testdir, 'quadplane.parm'), valgrind=valgrind, gdb=gdb)
|
||||
mavproxy = util.start_MAVProxy_SIL('QuadPlane', options=options)
|
||||
mavproxy.expect('Telemetry log: (\S+)')
|
||||
logfile = mavproxy.match.group(1)
|
||||
|
Loading…
Reference in New Issue
Block a user