|
|
|
@ -567,6 +567,19 @@ def start_vehicle(binary, autotest, opts, stuff, loc=None):
@@ -567,6 +567,19 @@ def start_vehicle(binary, autotest, opts, stuff, loc=None):
|
|
|
|
|
gdb_commands_file.close() |
|
|
|
|
cmd.extend(["-x", gdb_commands_file.name]) |
|
|
|
|
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: |
|
|
|
|
cmd_name += " (strace)" |
|
|
|
|
cmd.append("strace") |
|
|
|
@ -842,6 +855,14 @@ group_sim.add_option("-g", "--gdb-stopped",
@@ -842,6 +855,14 @@ group_sim.add_option("-g", "--gdb-stopped",
|
|
|
|
|
action='store_true', |
|
|
|
|
default=False, |
|
|
|
|
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", |
|
|
|
|
default=0, |
|
|
|
|
type='float', |
|
|
|
@ -978,23 +999,27 @@ if cmd_opts.hil:
@@ -978,23 +999,27 @@ if cmd_opts.hil:
|
|
|
|
|
if cmd_opts.callgrind: |
|
|
|
|
print("May not use callgrind with hil") |
|
|
|
|
sys.exit(1) |
|
|
|
|
if cmd_opts.gdb or cmd_opts.gdb_stopped: |
|
|
|
|
print("May not use gdb with hil") |
|
|
|
|
if cmd_opts.gdb or cmd_opts.gdb_stopped or cmd_opts.lldb or cmd_opts.lldb_stopped: |
|
|
|
|
print("May not use gdb or lldb with hil") |
|
|
|
|
sys.exit(1) |
|
|
|
|
if cmd_opts.strace: |
|
|
|
|
print("May not use strace with hil") |
|
|
|
|
sys.exit(1) |
|
|
|
|
|
|
|
|
|
if cmd_opts.valgrind and (cmd_opts.gdb or cmd_opts.gdb_stopped): |
|
|
|
|
print("May not use valgrind with gdb") |
|
|
|
|
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 or lldb") |
|
|
|
|
sys.exit(1) |
|
|
|
|
|
|
|
|
|
if cmd_opts.valgrind and cmd_opts.callgrind: |
|
|
|
|
print("May not use valgrind with callgrind") |
|
|
|
|
sys.exit(1) |
|
|
|
|
|
|
|
|
|
if cmd_opts.strace and (cmd_opts.gdb or cmd_opts.gdb_stopped): |
|
|
|
|
print("May not use strace with gdb") |
|
|
|
|
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 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) |
|
|
|
|
|
|
|
|
|
if cmd_opts.strace and cmd_opts.valgrind: |
|
|
|
|