Browse Source

autotest: start GDB in tui mode by default

zr-v5.1
Peter Barker 4 years ago committed by Peter Barker
parent
commit
0b517cfc57
  1. 5
      Tools/autotest/autotest.py
  2. 3
      Tools/autotest/common.py
  3. 3
      Tools/autotest/pysim/util.py

5
Tools/autotest/autotest.py

@ -484,6 +484,7 @@ def run_step(step): @@ -484,6 +484,7 @@ def run_step(step):
"use_map": opts.map,
"valgrind": opts.valgrind,
"gdb": opts.gdb,
"gdb_no_tui": opts.gdb_no_tui,
"lldb": opts.lldb,
"gdbserver": opts.gdbserver,
"breakpoints": opts.breakpoint,
@ -902,6 +903,10 @@ if __name__ == "__main__": @@ -902,6 +903,10 @@ if __name__ == "__main__":
default=False,
action='store_true',
help='run ArduPilot binaries under gdb')
group_sim.add_option("--gdb-no-tui",
default=False,
action='store_true',
help='when running under GDB do NOT start in TUI mode')
group_sim.add_option("--gdbserver",
default=False,
action='store_true',

3
Tools/autotest/common.py

@ -1196,6 +1196,7 @@ class AutoTest(ABC): @@ -1196,6 +1196,7 @@ class AutoTest(ABC):
binary,
valgrind=False,
gdb=False,
gdb_no_tui=False,
speedup=None,
frame=None,
params=None,
@ -1220,6 +1221,7 @@ class AutoTest(ABC): @@ -1220,6 +1221,7 @@ class AutoTest(ABC):
self.binary = binary
self.valgrind = valgrind
self.gdb = gdb
self.gdb_no_tui = gdb_no_tui
self.lldb = lldb
self.frame = frame
self.params = params
@ -5929,6 +5931,7 @@ Also, ignores heartbeats not from our target system''' @@ -5929,6 +5931,7 @@ Also, ignores heartbeats not from our target system'''
"breakpoints": self.breakpoints,
"disable_breakpoints": self.disable_breakpoints,
"gdb": self.gdb,
"gdb_no_tui": self.gdb_no_tui,
"gdbserver": self.gdbserver,
"lldb": self.lldb,
"home": self.sitl_home(),

3
Tools/autotest/pysim/util.py

@ -278,6 +278,7 @@ def kill_mac_terminal(): @@ -278,6 +278,7 @@ def kill_mac_terminal():
def start_SITL(binary,
valgrind=False,
gdb=False,
gdb_no_tui=False,
wipe=False,
synthetic_clock=True,
home=None,
@ -332,6 +333,8 @@ def start_SITL(binary, @@ -332,6 +333,8 @@ def start_SITL(binary,
f.write("b %s\n" % (breakpoint,))
if disable_breakpoints:
f.write("disable\n")
if not gdb_no_tui:
f.write("tui enable\n")
f.write("r\n")
f.close()
if sys.platform == "darwin" and os.getenv('DISPLAY'):

Loading…
Cancel
Save