mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
autotest: add --callgrind option
This commit is contained in:
parent
ad4b934b3c
commit
746d9fda8d
@ -510,6 +510,7 @@ def run_step(step):
|
||||
"viewerip": opts.viewerip,
|
||||
"use_map": opts.map,
|
||||
"valgrind": opts.valgrind,
|
||||
"callgrind": opts.callgrind,
|
||||
"gdb": opts.gdb,
|
||||
"gdb_no_tui": opts.gdb_no_tui,
|
||||
"lldb": opts.lldb,
|
||||
@ -962,6 +963,10 @@ if __name__ == "__main__":
|
||||
default=False,
|
||||
action='store_true',
|
||||
help='run ArduPilot binaries under valgrind')
|
||||
group_sim.add_option("", "--callgrind",
|
||||
action='store_true',
|
||||
default=False,
|
||||
help="enable valgrind for performance analysis (slow!!)")
|
||||
group_sim.add_option("--gdb",
|
||||
default=False,
|
||||
action='store_true',
|
||||
@ -1032,6 +1037,8 @@ if __name__ == "__main__":
|
||||
# adjust if we're running in a regime which may slow us down e.g. Valgrind
|
||||
if opts.valgrind:
|
||||
opts.timeout *= 10
|
||||
elif opts.callgrind:
|
||||
opts.timeout *= 10
|
||||
elif opts.gdb:
|
||||
opts.timeout = None
|
||||
|
||||
|
@ -1445,6 +1445,7 @@ class AutoTest(ABC):
|
||||
def __init__(self,
|
||||
binary,
|
||||
valgrind=False,
|
||||
callgrind=False,
|
||||
gdb=False,
|
||||
gdb_no_tui=False,
|
||||
speedup=None,
|
||||
@ -1473,6 +1474,7 @@ class AutoTest(ABC):
|
||||
|
||||
self.binary = binary
|
||||
self.valgrind = valgrind
|
||||
self.callgrind = callgrind
|
||||
self.gdb = gdb
|
||||
self.gdb_no_tui = gdb_no_tui
|
||||
self.lldb = lldb
|
||||
@ -1842,7 +1844,7 @@ class AutoTest(ABC):
|
||||
old_bootcount = self.get_parameter('STAT_BOOTCNT')
|
||||
# ardupilot SITL may actually NAK the reboot; replace with
|
||||
# run_cmd when we don't do that.
|
||||
if self.valgrind:
|
||||
if self.valgrind or self.callgrind:
|
||||
self.reboot_check_valgrind_log()
|
||||
self.progress("Stopping and restarting SITL")
|
||||
if getattr(self, 'valgrind_restart_customisations', None) is not None:
|
||||
@ -2426,7 +2428,7 @@ class AutoTest(ABC):
|
||||
|
||||
# stash our arguments in case we need to preserve them in
|
||||
# reboot_sitl with Valgrind active:
|
||||
if self.valgrind:
|
||||
if self.valgrind or self.callgrind:
|
||||
self.valgrind_restart_model = model
|
||||
self.valgrind_restart_defaults_filepath = defaults_filepath
|
||||
self.valgrind_restart_customisations = customisations
|
||||
@ -6541,7 +6543,7 @@ Also, ignores heartbeats not from our target system'''
|
||||
# determine a good pexpect timeout for reading MAVProxy's
|
||||
# output; some regmes may require longer timeouts.
|
||||
pexpect_timeout = 60
|
||||
if self.valgrind:
|
||||
if self.valgrind or self.callgrind:
|
||||
pexpect_timeout *= 10
|
||||
|
||||
mavproxy = util.start_MAVProxy_SITL(
|
||||
@ -6578,6 +6580,7 @@ Also, ignores heartbeats not from our target system'''
|
||||
"home": self.sitl_home(),
|
||||
"speedup": self.speedup,
|
||||
"valgrind": self.valgrind,
|
||||
"callgrind": self.callgrind,
|
||||
"wipe": True,
|
||||
}
|
||||
start_sitl_args.update(**sitl_args)
|
||||
@ -7712,7 +7715,7 @@ Also, ignores heartbeats not from our target system'''
|
||||
rate = float(mavproxy.match.group(1))
|
||||
self.progress("Rate: %f" % rate)
|
||||
desired_rate = 50
|
||||
if self.valgrind:
|
||||
if self.valgrind or self.callgrind:
|
||||
desired_rate /= 10
|
||||
if rate < desired_rate:
|
||||
raise NotAchievedException("Exceptionally low transfer rate (%u < %u)" % (rate, desired_rate))
|
||||
@ -10469,7 +10472,7 @@ switch value'''
|
||||
self.drain_mav(quiet=True)
|
||||
tnow = self.get_sim_time_cached()
|
||||
timeout = 30
|
||||
if self.valgrind:
|
||||
if self.valgrind or self.callgrind:
|
||||
timeout *= 10
|
||||
if tnow - tstart > timeout:
|
||||
raise NotAchievedException("Did not get parameter via mavlite")
|
||||
|
@ -296,6 +296,7 @@ def kill_mac_terminal():
|
||||
|
||||
def start_SITL(binary,
|
||||
valgrind=False,
|
||||
callgrind=False,
|
||||
gdb=False,
|
||||
gdb_no_tui=False,
|
||||
wipe=False,
|
||||
@ -317,7 +318,7 @@ def start_SITL(binary,
|
||||
|
||||
"""Launch a SITL instance."""
|
||||
cmd = []
|
||||
if valgrind and os.path.exists('/usr/bin/valgrind'):
|
||||
if (callgrind or valgrind) and os.path.exists('/usr/bin/valgrind'):
|
||||
# we specify a prefix for vgdb-pipe because on Vagrant virtual
|
||||
# machines the pipes are created on the mountpoint for the
|
||||
# shared directory with the host machine. mmap's,
|
||||
@ -332,6 +333,8 @@ def start_SITL(binary,
|
||||
'--vgdb-prefix=%s' % vgdb_prefix,
|
||||
'-q',
|
||||
'--log-file=%s' % log_file])
|
||||
if callgrind:
|
||||
cmd.extend(["--tool=callgrind"])
|
||||
if gdbserver:
|
||||
cmd.extend(['gdbserver', 'localhost:3333'])
|
||||
if gdb:
|
||||
|
Loading…
Reference in New Issue
Block a user