mirror of https://github.com/ArduPilot/ardupilot
Tools: support lldb debugging for sim_vehicle and autotest
This commit is contained in:
parent
9d67a9423f
commit
30c86eb768
|
@ -378,6 +378,7 @@ def run_step(step):
|
||||||
"use_map": opts.map,
|
"use_map": opts.map,
|
||||||
"valgrind": opts.valgrind,
|
"valgrind": opts.valgrind,
|
||||||
"gdb": opts.gdb,
|
"gdb": opts.gdb,
|
||||||
|
"lldb": opts.lldb,
|
||||||
"gdbserver": opts.gdbserver,
|
"gdbserver": opts.gdbserver,
|
||||||
"breakpoints": opts.breakpoint,
|
"breakpoints": opts.breakpoint,
|
||||||
"disable_breakpoints": opts.disable_breakpoints,
|
"disable_breakpoints": opts.disable_breakpoints,
|
||||||
|
@ -723,6 +724,10 @@ if __name__ == "__main__":
|
||||||
default=False,
|
default=False,
|
||||||
action='store_true',
|
action='store_true',
|
||||||
help='run ArduPilot binaries under gdbserver')
|
help='run ArduPilot binaries under gdbserver')
|
||||||
|
group_sim.add_option("--lldb",
|
||||||
|
default=False,
|
||||||
|
action='store_true',
|
||||||
|
help='run ArduPilot binaries under lldb')
|
||||||
group_sim.add_option("-B", "--breakpoint",
|
group_sim.add_option("-B", "--breakpoint",
|
||||||
type='string',
|
type='string',
|
||||||
action="append",
|
action="append",
|
||||||
|
|
|
@ -170,6 +170,7 @@ class AutoTest(ABC):
|
||||||
frame=None,
|
frame=None,
|
||||||
params=None,
|
params=None,
|
||||||
gdbserver=False,
|
gdbserver=False,
|
||||||
|
lldb=False,
|
||||||
breakpoints=[],
|
breakpoints=[],
|
||||||
disable_breakpoints=False,
|
disable_breakpoints=False,
|
||||||
viewerip=None,
|
viewerip=None,
|
||||||
|
@ -179,6 +180,7 @@ class AutoTest(ABC):
|
||||||
self.binary = binary
|
self.binary = binary
|
||||||
self.valgrind = valgrind
|
self.valgrind = valgrind
|
||||||
self.gdb = gdb
|
self.gdb = gdb
|
||||||
|
self.lldb = lldb
|
||||||
self.frame = frame
|
self.frame = frame
|
||||||
self.params = params
|
self.params = params
|
||||||
self.gdbserver = gdbserver
|
self.gdbserver = gdbserver
|
||||||
|
@ -2134,6 +2136,7 @@ class AutoTest(ABC):
|
||||||
defaults_file=self.defaults_filepath(),
|
defaults_file=self.defaults_filepath(),
|
||||||
gdb=self.gdb,
|
gdb=self.gdb,
|
||||||
gdbserver=self.gdbserver,
|
gdbserver=self.gdbserver,
|
||||||
|
lldb=self.lldb,
|
||||||
home=self.sitl_home(),
|
home=self.sitl_home(),
|
||||||
model=self.frame,
|
model=self.frame,
|
||||||
speedup=self.speedup,
|
speedup=self.speedup,
|
||||||
|
|
|
@ -227,7 +227,6 @@ def kill_screen_gdb():
|
||||||
cmd = ["screen", "-X", "-S", "ardupilot-gdb", "quit"]
|
cmd = ["screen", "-X", "-S", "ardupilot-gdb", "quit"]
|
||||||
subprocess.Popen(cmd)
|
subprocess.Popen(cmd)
|
||||||
|
|
||||||
|
|
||||||
def start_SITL(binary,
|
def start_SITL(binary,
|
||||||
valgrind=False,
|
valgrind=False,
|
||||||
gdb=False,
|
gdb=False,
|
||||||
|
@ -241,7 +240,8 @@ def start_SITL(binary,
|
||||||
gdbserver=False,
|
gdbserver=False,
|
||||||
breakpoints=[],
|
breakpoints=[],
|
||||||
disable_breakpoints=False,
|
disable_breakpoints=False,
|
||||||
vicon=False):
|
vicon=False,
|
||||||
|
lldb=False):
|
||||||
"""Launch a SITL instance."""
|
"""Launch a SITL instance."""
|
||||||
cmd = []
|
cmd = []
|
||||||
if valgrind and os.path.exists('/usr/bin/valgrind'):
|
if valgrind and os.path.exists('/usr/bin/valgrind'):
|
||||||
|
@ -289,6 +289,19 @@ def start_SITL(binary,
|
||||||
'-m',
|
'-m',
|
||||||
'-S', 'ardupilot-gdb',
|
'-S', 'ardupilot-gdb',
|
||||||
'gdb', '-x', '/tmp/x.gdb', binary, '--args'])
|
'gdb', '-x', '/tmp/x.gdb', binary, '--args'])
|
||||||
|
elif lldb:
|
||||||
|
f = open("/tmp/x.lldb", "w")
|
||||||
|
for breakpoint in breakpoints:
|
||||||
|
f.write("b %s\n" % (breakpoint,))
|
||||||
|
if disable_breakpoints:
|
||||||
|
f.write("disable\n")
|
||||||
|
f.write("settings set target.process.stop-on-exec false\n")
|
||||||
|
f.write("process launch\n")
|
||||||
|
f.close()
|
||||||
|
if os.environ.get('DISPLAY'):
|
||||||
|
cmd.extend(['xterm', '-e', 'lldb', '-s','/tmp/x.lldb', '--'])
|
||||||
|
else:
|
||||||
|
raise RuntimeError("DISPLAY was not set")
|
||||||
|
|
||||||
cmd.append(binary)
|
cmd.append(binary)
|
||||||
if wipe:
|
if wipe:
|
||||||
|
@ -328,7 +341,7 @@ def start_SITL(binary,
|
||||||
pexpect_autoclose(child)
|
pexpect_autoclose(child)
|
||||||
# give time for parameters to properly setup
|
# give time for parameters to properly setup
|
||||||
time.sleep(3)
|
time.sleep(3)
|
||||||
if gdb:
|
if gdb or lldb:
|
||||||
# if we run GDB we do so in an xterm. "Waiting for
|
# if we run GDB we do so in an xterm. "Waiting for
|
||||||
# connection" is never going to appear on xterm's output.
|
# connection" is never going to appear on xterm's output.
|
||||||
# ... so let's give it another magic second.
|
# ... so let's give it another magic second.
|
||||||
|
|
|
@ -567,6 +567,19 @@ def start_vehicle(binary, autotest, opts, stuff, loc=None):
|
||||||
gdb_commands_file.close()
|
gdb_commands_file.close()
|
||||||
cmd.extend(["-x", gdb_commands_file.name])
|
cmd.extend(["-x", gdb_commands_file.name])
|
||||||
cmd.append("--args")
|
cmd.append("--args")
|
||||||
|
elif opts.lldb or opts.lldb_stopped:
|
||||||
|
cmd_name += " (lldb)"
|
||||||
|
cmd.append("lldb")
|
||||||
|
lldb_commands_file = tempfile.NamedTemporaryFile(mode='w', delete=False)
|
||||||
|
atexit.register(os.unlink, lldb_commands_file.name)
|
||||||
|
|
||||||
|
for breakpoint in opts.breakpoint:
|
||||||
|
lldb_commands_file.write("b %s\n" % (breakpoint,))
|
||||||
|
if not opts.lldb_stopped:
|
||||||
|
lldb_commands_file.write("process launch\n")
|
||||||
|
lldb_commands_file.close()
|
||||||
|
cmd.extend(["-s", lldb_commands_file.name])
|
||||||
|
cmd.append("--")
|
||||||
if opts.strace:
|
if opts.strace:
|
||||||
cmd_name += " (strace)"
|
cmd_name += " (strace)"
|
||||||
cmd.append("strace")
|
cmd.append("strace")
|
||||||
|
@ -842,6 +855,14 @@ group_sim.add_option("-g", "--gdb-stopped",
|
||||||
action='store_true',
|
action='store_true',
|
||||||
default=False,
|
default=False,
|
||||||
help="use gdb for debugging ardupilot (no auto-start)")
|
help="use gdb for debugging ardupilot (no auto-start)")
|
||||||
|
group_sim.add_option("--lldb",
|
||||||
|
action='store_true',
|
||||||
|
default=False,
|
||||||
|
help="use lldb for debugging ardupilot")
|
||||||
|
group_sim.add_option("--lldb-stopped",
|
||||||
|
action='store_true',
|
||||||
|
default=False,
|
||||||
|
help="use ldb for debugging ardupilot (no auto-start)")
|
||||||
group_sim.add_option("-d", "--delay-start",
|
group_sim.add_option("-d", "--delay-start",
|
||||||
default=0,
|
default=0,
|
||||||
type='float',
|
type='float',
|
||||||
|
@ -978,23 +999,27 @@ if cmd_opts.hil:
|
||||||
if cmd_opts.callgrind:
|
if cmd_opts.callgrind:
|
||||||
print("May not use callgrind with hil")
|
print("May not use callgrind with hil")
|
||||||
sys.exit(1)
|
sys.exit(1)
|
||||||
if cmd_opts.gdb or cmd_opts.gdb_stopped:
|
if cmd_opts.gdb or cmd_opts.gdb_stopped or cmd_opts.lldb or cmd_opts.lldb_stopped:
|
||||||
print("May not use gdb with hil")
|
print("May not use gdb or lldb with hil")
|
||||||
sys.exit(1)
|
sys.exit(1)
|
||||||
if cmd_opts.strace:
|
if cmd_opts.strace:
|
||||||
print("May not use strace with hil")
|
print("May not use strace with hil")
|
||||||
sys.exit(1)
|
sys.exit(1)
|
||||||
|
|
||||||
if cmd_opts.valgrind and (cmd_opts.gdb or cmd_opts.gdb_stopped):
|
if cmd_opts.valgrind and (cmd_opts.gdb or cmd_opts.gdb_stopped or cmd_opts.lldb or cmd_opts.lldb_stopped):
|
||||||
print("May not use valgrind with gdb")
|
print("May not use valgrind with gdb or lldb")
|
||||||
sys.exit(1)
|
sys.exit(1)
|
||||||
|
|
||||||
if cmd_opts.valgrind and cmd_opts.callgrind:
|
if cmd_opts.valgrind and cmd_opts.callgrind:
|
||||||
print("May not use valgrind with callgrind")
|
print("May not use valgrind with callgrind")
|
||||||
sys.exit(1)
|
sys.exit(1)
|
||||||
|
|
||||||
if cmd_opts.strace and (cmd_opts.gdb or cmd_opts.gdb_stopped):
|
if cmd_opts.strace and (cmd_opts.gdb or cmd_opts.gdb_stopped or cmd_opts.lldb or cmd_opts.lldb_stopped):
|
||||||
print("May not use strace with gdb")
|
print("May not use strace with gdb or lldb")
|
||||||
|
sys.exit(1)
|
||||||
|
|
||||||
|
if (cmd_opts.gdb or cmd_opts.gdb_stopped) and (cmd_opts.lldb or cmd_opts.lldb_stopped):
|
||||||
|
print("May not use lldb with gdb")
|
||||||
sys.exit(1)
|
sys.exit(1)
|
||||||
|
|
||||||
if cmd_opts.strace and cmd_opts.valgrind:
|
if cmd_opts.strace and cmd_opts.valgrind:
|
||||||
|
|
Loading…
Reference in New Issue