Tools: Adds GDBServer with screen option for debugging
This commit is contained in:
parent
db3c387916
commit
38297c4d19
@ -973,7 +973,7 @@ def setup_rc(mavproxy):
|
||||
mavproxy.send('rc 3 1000\n')
|
||||
|
||||
|
||||
def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None):
|
||||
def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False):
|
||||
"""Fly ArduCopter in SITL.
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
@ -1005,7 +1005,7 @@ def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fal
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sitl)
|
||||
|
||||
sitl = util.start_SITL(binary, model=frame, home=home, speedup=speedup_default, valgrind=valgrind, gdb=gdb)
|
||||
sitl = util.start_SITL(binary, model=frame, home=home, speedup=speedup_default, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
|
||||
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5'
|
||||
if viewerip:
|
||||
options += ' --out=%s:14550' % viewerip
|
||||
@ -1330,7 +1330,7 @@ def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fal
|
||||
return True
|
||||
|
||||
|
||||
def fly_CopterAVC(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None):
|
||||
def fly_CopterAVC(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False):
|
||||
"""Fly ArduCopter in SITL for AVC2013 mission."""
|
||||
global homeloc
|
||||
|
||||
@ -1358,7 +1358,7 @@ def fly_CopterAVC(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sitl)
|
||||
|
||||
sitl = util.start_SITL(binary, model='heli', home=home, speedup=speedup_default, valgrind=valgrind, gdb=gdb)
|
||||
sitl = util.start_SITL(binary, model='heli', home=home, speedup=speedup_default, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
|
||||
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=5'
|
||||
if viewerip:
|
||||
options += ' --out=%s:14550' % viewerip
|
||||
|
@ -440,7 +440,7 @@ def fly_mission(mavproxy, mav, filename, height_accuracy=-1, target_altitude=Non
|
||||
return True
|
||||
|
||||
|
||||
def fly_ArduPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=False):
|
||||
def fly_ArduPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, gdbserver=False):
|
||||
"""Fly ArduPlane in SITL.
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
@ -455,7 +455,7 @@ def fly_ArduPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
|
||||
options += ' --map'
|
||||
|
||||
sitl = util.start_SITL(binary, model='plane-elevrev', home=HOME_LOCATION, speedup=10,
|
||||
valgrind=valgrind, gdb=gdb,
|
||||
valgrind=valgrind, gdb=gdb, gdbserver=gdbserver,
|
||||
defaults_file=os.path.join(testdir, 'default_params/plane-jsbsim.parm'))
|
||||
mavproxy = util.start_MAVProxy_SITL('ArduPlane', options=options)
|
||||
mavproxy.expect('Telemetry log: (\S+)')
|
||||
|
@ -92,7 +92,7 @@ def dive_mission(mavproxy, mav, filename):
|
||||
print("Mission OK")
|
||||
return True
|
||||
|
||||
def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False):
|
||||
def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, gdbserver=False):
|
||||
"""Dive ArduSub in SITL.
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
@ -121,7 +121,7 @@ def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sitl)
|
||||
|
||||
sitl = util.start_SITL(binary, model='vectored', home=home, speedup=10, valgrind=valgrind, gdb=gdb)
|
||||
sitl = util.start_SITL(binary, model='vectored', home=home, speedup=10, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
|
||||
mavproxy = util.start_MAVProxy_SITL('ArduSub', options=options)
|
||||
mavproxy.expect('Telemetry log: (\S+)')
|
||||
logfile = mavproxy.match.group(1)
|
||||
|
@ -223,22 +223,22 @@ def run_step(step):
|
||||
return get_default_params(vehicle, binary)
|
||||
|
||||
if step == 'fly.ArduCopter':
|
||||
return arducopter.fly_ArduCopter(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, frame=opts.frame)
|
||||
return arducopter.fly_ArduCopter(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, frame=opts.frame, gdbserver=opts.gdbserver)
|
||||
|
||||
if step == 'fly.CopterAVC':
|
||||
return arducopter.fly_CopterAVC(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, frame=opts.frame)
|
||||
return arducopter.fly_CopterAVC(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, frame=opts.frame, gdbserver=opts.gdbserver)
|
||||
|
||||
if step == 'fly.ArduPlane':
|
||||
return arduplane.fly_ArduPlane(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb)
|
||||
return arduplane.fly_ArduPlane(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, gdbserver=opts.gdbserver)
|
||||
|
||||
if step == 'fly.QuadPlane':
|
||||
return quadplane.fly_QuadPlane(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb)
|
||||
return quadplane.fly_QuadPlane(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, gdbserver=opts.gdbserver)
|
||||
|
||||
if step == 'drive.APMrover2':
|
||||
return apmrover2.drive_APMrover2(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, frame=opts.frame)
|
||||
|
||||
return apmrover2.drive_APMrover2(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, frame=opts.frame, gdbserver=opts.gdbserver)
|
||||
|
||||
if step == 'dive.ArduSub':
|
||||
return ardusub.dive_ArduSub(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb)
|
||||
return ardusub.dive_ArduSub(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, gdbserver=opts.gdbserver)
|
||||
|
||||
if step == 'build.All':
|
||||
return build_all()
|
||||
@ -449,6 +449,7 @@ if __name__ == "__main__":
|
||||
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')
|
||||
parser.add_option("--frame", type='string', default=None, help='specify frame type')
|
||||
parser.add_option("--gdbserver", default=False, action='store_true', help='run ArduPilot binaries under gdbserver')
|
||||
|
||||
opts, args = parser.parse_args()
|
||||
|
||||
|
@ -187,7 +187,9 @@ def valgrind_log_filepath(binary, model):
|
||||
return make_safe_filename('%s-%s-valgrind.log' % (os.path.basename(binary), model,))
|
||||
|
||||
|
||||
def start_SITL(binary, valgrind=False, gdb=False, wipe=False, synthetic_clock=True, home=None, model=None, speedup=1, defaults_file=None, unhide_parameters=False):
|
||||
def start_SITL(binary, valgrind=False, gdb=False, wipe=False,
|
||||
synthetic_clock=True, home=None, model=None, speedup=1, defaults_file=None,
|
||||
unhide_parameters=False, gdbserver=False):
|
||||
"""Launch a SITL instance."""
|
||||
cmd = []
|
||||
if valgrind and os.path.exists('/usr/bin/valgrind'):
|
||||
@ -197,7 +199,13 @@ def start_SITL(binary, valgrind=False, gdb=False, wipe=False, synthetic_clock=Tr
|
||||
f.write("r\n")
|
||||
f.close()
|
||||
cmd.extend(['xterm', '-e', 'gdb', '-x', '/tmp/x.gdb', '--args'])
|
||||
|
||||
if gdbserver:
|
||||
f = open("/tmp/x.gdb", "w")
|
||||
f.write("target extended-remote localhost:3333\nc\n")
|
||||
f.close()
|
||||
cmd.extend(['gdbserver', 'localhost:3333'])
|
||||
run_cmd('screen -d -m -S ardupilot-gdb bash -c "gdb -x /tmp/x.gdb"')
|
||||
|
||||
cmd.append(binary)
|
||||
if wipe:
|
||||
cmd.append('-w')
|
||||
|
@ -44,7 +44,7 @@ def fly_mission(mavproxy, mav, filename, fence, height_accuracy=-1):
|
||||
return True
|
||||
|
||||
|
||||
def fly_QuadPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=False):
|
||||
def fly_QuadPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, gdbserver=False):
|
||||
"""Fly QuadPlane in SITL.
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
@ -59,7 +59,7 @@ def fly_QuadPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
|
||||
options += ' --map'
|
||||
|
||||
sitl = util.start_SITL(binary, model='quadplane', wipe=True, home=HOME_LOCATION, speedup=10,
|
||||
defaults_file=os.path.join(testdir, 'default_params/quadplane.parm'), valgrind=valgrind, gdb=gdb)
|
||||
defaults_file=os.path.join(testdir, 'default_params/quadplane.parm'), valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
|
||||
mavproxy = util.start_MAVProxy_SITL('QuadPlane', options=options)
|
||||
mavproxy.expect('Telemetry log: (\S+)')
|
||||
logfile = mavproxy.match.group(1)
|
||||
|
Loading…
Reference in New Issue
Block a user