Tools: autotest: add ability to add breakpoints in autotest

This commit is contained in:
Peter Barker 2018-07-23 17:06:00 +10:00
parent 8c44a0d8c8
commit 6dd8dbeb40
7 changed files with 40 additions and 5 deletions

View File

@ -36,6 +36,7 @@ class AutoTestRover(AutoTest):
frame=None,
params=None,
gdbserver=False,
breakpoints=[],
**kwargs):
super(AutoTestRover, self).__init__(**kwargs)
self.binary = binary
@ -44,6 +45,7 @@ class AutoTestRover(AutoTest):
self.frame = frame
self.params = params
self.gdbserver = gdbserver
self.breakpoints = breakpoints
self.home = "%f,%f,%u,%u" % (HOME.lat,
HOME.lng,
@ -69,6 +71,7 @@ class AutoTestRover(AutoTest):
valgrind=self.valgrind,
gdb=self.gdb,
gdbserver=self.gdbserver,
breakpoints=self.breakpoints,
wipe=True)
self.mavproxy = util.start_MAVProxy_SITL(
'APMrover2', options=self.mavproxy_options())

View File

@ -38,6 +38,7 @@ class AutoTestCopter(AutoTest):
frame=None,
params=None,
gdbserver=False,
breakpoints=[],
**kwargs):
super(AutoTestCopter, self).__init__(**kwargs)
self.binary = binary
@ -46,6 +47,7 @@ class AutoTestCopter(AutoTest):
self.frame = frame
self.params = params
self.gdbserver = gdbserver
self.breakpoints = breakpoints
self.home = "%f,%f,%u,%u" % (HOME.lat,
HOME.lng,
@ -93,6 +95,7 @@ class AutoTestCopter(AutoTest):
valgrind=self.valgrind,
gdb=self.gdb,
gdbserver=self.gdbserver,
breakpoints=self.breakpoints,
vicon=True,
wipe=True)
self.mavproxy = util.start_MAVProxy_SITL(

View File

@ -28,6 +28,7 @@ class AutoTestPlane(AutoTest):
frame=None,
params=None,
gdbserver=False,
breakpoints=[],
**kwargs):
super(AutoTestPlane, self).__init__(**kwargs)
self.binary = binary
@ -36,6 +37,7 @@ class AutoTestPlane(AutoTest):
self.frame = frame
self.params = params
self.gdbserver = gdbserver
self.breakpoints = breakpoints
self.home = "%f,%f,%u,%u" % (HOME.lat,
HOME.lng,
@ -64,7 +66,8 @@ class AutoTestPlane(AutoTest):
defaults_file=defaults_file,
valgrind=self.valgrind,
gdb=self.gdb,
gdbserver=self.gdbserver)
gdbserver=self.gdbserver,
breakpoints=self.breakpoints)
self.mavproxy = util.start_MAVProxy_SITL(
'ArduPlane', options=self.mavproxy_options())
self.mavproxy.expect('Telemetry log: (\S+)\r\n')

View File

@ -25,6 +25,7 @@ class AutoTestSub(AutoTest):
frame=None,
params=None,
gdbserver=False,
breakpoints=[],
**kwargs):
super(AutoTestSub, self).__init__(**kwargs)
self.binary = binary
@ -33,6 +34,7 @@ class AutoTestSub(AutoTest):
self.frame = frame
self.params = params
self.gdbserver = gdbserver
self.breakpoints = breakpoints
self.home = "%f,%f,%u,%u" % (HOME.lat,
HOME.lng,
@ -58,6 +60,7 @@ class AutoTestSub(AutoTest):
valgrind=self.valgrind,
gdb=self.gdb,
gdbserver=self.gdbserver,
breakpoints=self.breakpoints,
wipe=True)
self.mavproxy = util.start_MAVProxy_SITL(
'ArduSub', options=self.mavproxy_options())

View File

@ -308,6 +308,7 @@ def run_step(step):
"valgrind": opts.valgrind,
"gdb": opts.gdb,
"gdbserver": opts.gdbserver,
"breakpoints": opts.breakpoint,
}
if opts.speedup is not None:
fly_opts["speedup"] = opts.speedup
@ -604,6 +605,11 @@ if __name__ == "__main__":
default=False,
action='store_true',
help='run ArduPilot binaries under gdbserver')
group_sim.add_option("-B", "--breakpoint",
type='string',
action="append",
default=[],
help="add a breakpoint at given location in debugger")
parser.add_option_group(group_sim)
opts, args = parser.parse_args()

View File

@ -190,9 +190,18 @@ 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, gdbserver=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,
breakpoints=[],
vicon=False):
"""Launch a SITL instance."""
cmd = []
@ -214,10 +223,14 @@ def start_SITL(binary, valgrind=False, gdb=False, wipe=False,
# attach gdb to the gdbserver:
f = open("/tmp/x.gdb", "w")
f.write("target extended-remote localhost:3333\nc\n")
for breakpoint in breakpoints:
f.write("b %s\n" % (breakpoint,))
f.close()
run_cmd('screen -d -m -S ardupilot-gdb bash -c "gdb -x /tmp/x.gdb"')
elif gdb:
f = open("/tmp/x.gdb", "w")
for breakpoint in breakpoints:
f.write("b %s\n" % (breakpoint,))
f.write("r\n")
f.close()
cmd.extend(['xterm', '-e', 'gdb', '-x', '/tmp/x.gdb', '--args'])

View File

@ -26,6 +26,7 @@ class AutoTestQuadPlane(AutoTest):
frame=None,
params=None,
gdbserver=False,
breakpoints=[],
**kwargs):
super(AutoTestQuadPlane, self).__init__(**kwargs)
self.binary = binary
@ -34,6 +35,7 @@ class AutoTestQuadPlane(AutoTest):
self.frame = frame
self.params = params
self.gdbserver = gdbserver
self.breakpoints = breakpoints
self.home = "%f,%f,%u,%u" % (HOME.lat,
HOME.lng,
@ -64,7 +66,9 @@ class AutoTestQuadPlane(AutoTest):
defaults_file=defaults_file,
valgrind=self.valgrind,
gdb=self.gdb,
gdbserver=self.gdbserver)
gdbserver=self.gdbserver,
breakpoints=self.breakpoints,
)
self.mavproxy = util.start_MAVProxy_SITL(
'QuadPlane', options=self.mavproxy_options())
self.mavproxy.expect('Telemetry log: (\S+)\r\n')