diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 857fe8b320..5a2f99c1c9 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -380,6 +380,7 @@ def run_step(step): "gdb": opts.gdb, "gdbserver": opts.gdbserver, "breakpoints": opts.breakpoint, + "disable_breakpoints": opts.disable_breakpoints, "frame": opts.frame, "_show_test_timings": opts.show_test_timings, } @@ -727,6 +728,10 @@ if __name__ == "__main__": action="append", default=[], help="add a breakpoint at given location in debugger") + group_sim.add_option("--disable-breakpoints", + default=False, + action='store_true', + help="disable all breakpoints before starting") parser.add_option_group(group_sim) opts, args = parser.parse_args() diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 3e100662b7..1ad646c4f2 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -169,6 +169,7 @@ class AutoTest(ABC): params=None, gdbserver=False, breakpoints=[], + disable_breakpoints=False, viewerip=None, use_map=False, _show_test_timings=False): @@ -180,6 +181,7 @@ class AutoTest(ABC): self.params = params self.gdbserver = gdbserver self.breakpoints = breakpoints + self.disable_breakpoints = disable_breakpoints self.speedup = speedup self.mavproxy = None @@ -2007,6 +2009,7 @@ class AutoTest(ABC): self.progress("Starting simulator") self.sitl = util.start_SITL(self.binary, breakpoints=self.breakpoints, + disable_breakpoints=self.disable_breakpoints, defaults_file=self.defaults_filepath(), gdb=self.gdb, gdbserver=self.gdbserver, diff --git a/Tools/autotest/pysim/util.py b/Tools/autotest/pysim/util.py index c1cb44145b..eb4b07321e 100644 --- a/Tools/autotest/pysim/util.py +++ b/Tools/autotest/pysim/util.py @@ -227,6 +227,7 @@ def start_SITL(binary, unhide_parameters=False, gdbserver=False, breakpoints=[], + disable_breakpoints=False, vicon=False): """Launch a SITL instance.""" cmd = [] @@ -253,6 +254,8 @@ def start_SITL(binary, f.write("target extended-remote localhost:3333\nc\n") for breakpoint in breakpoints: f.write("b %s\n" % (breakpoint,)) + if disable_breakpoints: + f.write("disable\n") f.close() run_cmd('screen -d -m -S ardupilot-gdbserver ' 'bash -c "gdb -x /tmp/x.gdb"') @@ -260,6 +263,8 @@ def start_SITL(binary, f = open("/tmp/x.gdb", "w") for breakpoint in breakpoints: f.write("b %s\n" % (breakpoint,)) + if disable_breakpoints: + f.write("disable\n") f.write("r\n") f.close() if os.environ.get('DISPLAY'):