mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Tools: autotest: print time taken for each test
This commit is contained in:
parent
bf4dc2d3b7
commit
cf2c0ec334
@ -372,6 +372,7 @@ def run_step(step):
|
|||||||
"gdbserver": opts.gdbserver,
|
"gdbserver": opts.gdbserver,
|
||||||
"breakpoints": opts.breakpoint,
|
"breakpoints": opts.breakpoint,
|
||||||
"frame": opts.frame,
|
"frame": opts.frame,
|
||||||
|
"_show_test_timings": opts.show_test_timings,
|
||||||
}
|
}
|
||||||
if opts.speedup is not None:
|
if opts.speedup is not None:
|
||||||
fly_opts["speedup"] = opts.speedup
|
fly_opts["speedup"] = opts.speedup
|
||||||
@ -644,6 +645,10 @@ if __name__ == "__main__":
|
|||||||
type='string',
|
type='string',
|
||||||
default=None,
|
default=None,
|
||||||
help='specify frame type')
|
help='specify frame type')
|
||||||
|
parser.add_option("--show-test-timings",
|
||||||
|
action="store_true",
|
||||||
|
default=False,
|
||||||
|
help="show how long each test took to run")
|
||||||
|
|
||||||
group_build = optparse.OptionGroup(parser, "Build options")
|
group_build = optparse.OptionGroup(parser, "Build options")
|
||||||
group_build.add_option("--no-configure",
|
group_build.add_option("--no-configure",
|
||||||
|
@ -154,7 +154,8 @@ class AutoTest(ABC):
|
|||||||
"""
|
"""
|
||||||
def __init__(self,
|
def __init__(self,
|
||||||
viewerip=None,
|
viewerip=None,
|
||||||
use_map=False):
|
use_map=False,
|
||||||
|
_show_test_timings=False):
|
||||||
self.mavproxy = None
|
self.mavproxy = None
|
||||||
self.mav = None
|
self.mav = None
|
||||||
self.viewerip = viewerip
|
self.viewerip = viewerip
|
||||||
@ -169,6 +170,8 @@ class AutoTest(ABC):
|
|||||||
self.forced_post_test_sitl_reboots = 0
|
self.forced_post_test_sitl_reboots = 0
|
||||||
self.skip_list = []
|
self.skip_list = []
|
||||||
self.run_tests_called = False
|
self.run_tests_called = False
|
||||||
|
self._show_test_timings = _show_test_timings
|
||||||
|
self.test_timings = dict()
|
||||||
|
|
||||||
@staticmethod
|
@staticmethod
|
||||||
def progress(text):
|
def progress(text):
|
||||||
@ -1524,6 +1527,20 @@ class AutoTest(ABC):
|
|||||||
self.forced_post_test_sitl_reboots += 1
|
self.forced_post_test_sitl_reboots += 1
|
||||||
self.reboot_sitl() # that'll learn it
|
self.reboot_sitl() # that'll learn it
|
||||||
|
|
||||||
|
def show_test_timings_key_sorter(self, t):
|
||||||
|
(k, v) = t
|
||||||
|
return ((v, k))
|
||||||
|
|
||||||
|
def show_test_timings(self):
|
||||||
|
longest = 0
|
||||||
|
for desc in self.test_timings.keys():
|
||||||
|
if len(desc) > longest:
|
||||||
|
longest = len(desc)
|
||||||
|
for desc, time in sorted(self.test_timings.iteritems(),
|
||||||
|
key=self.show_test_timings_key_sorter):
|
||||||
|
fmt = "%" + str(longest) + "s: %.2fs"
|
||||||
|
self.progress(fmt % (desc, time))
|
||||||
|
|
||||||
def run_one_test(self, name, desc, test_function, interact=False):
|
def run_one_test(self, name, desc, test_function, interact=False):
|
||||||
'''new-style run-one-test used by run_tests'''
|
'''new-style run-one-test used by run_tests'''
|
||||||
test_output_filename = self.buildlogs_path("%s-%s.txt" %
|
test_output_filename = self.buildlogs_path("%s-%s.txt" %
|
||||||
@ -1535,11 +1552,14 @@ class AutoTest(ABC):
|
|||||||
|
|
||||||
self.context_push()
|
self.context_push()
|
||||||
|
|
||||||
|
start_time = time.time()
|
||||||
|
|
||||||
try:
|
try:
|
||||||
self.check_rc_defaults()
|
self.check_rc_defaults()
|
||||||
self.change_mode(self.default_mode())
|
self.change_mode(self.default_mode())
|
||||||
test_function()
|
test_function()
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
|
self.test_timings[desc] = time.time() - start_time
|
||||||
self.progress("Exception caught: %s" % traceback.format_exc(e))
|
self.progress("Exception caught: %s" % traceback.format_exc(e))
|
||||||
self.context_pop()
|
self.context_pop()
|
||||||
self.progress('FAILED: "%s": %s (see %s)' %
|
self.progress('FAILED: "%s": %s (see %s)' %
|
||||||
@ -1552,6 +1572,7 @@ class AutoTest(ABC):
|
|||||||
tee = None
|
tee = None
|
||||||
self.check_sitl_reset()
|
self.check_sitl_reset()
|
||||||
return
|
return
|
||||||
|
self.test_timings[desc] = time.time() - start_time
|
||||||
self.context_pop()
|
self.context_pop()
|
||||||
self.progress('PASSED: "%s"' % prettyname)
|
self.progress('PASSED: "%s"' % prettyname)
|
||||||
tee.close()
|
tee.close()
|
||||||
@ -2103,6 +2124,8 @@ switch value'''
|
|||||||
return []
|
return []
|
||||||
|
|
||||||
def post_tests_announcements(self):
|
def post_tests_announcements(self):
|
||||||
|
if self._show_test_timings:
|
||||||
|
self.show_test_timings()
|
||||||
if self.forced_post_test_sitl_reboots != 0:
|
if self.forced_post_test_sitl_reboots != 0:
|
||||||
print("Had to force-reset SITL %u times" %
|
print("Had to force-reset SITL %u times" %
|
||||||
(self.forced_post_test_sitl_reboots,))
|
(self.forced_post_test_sitl_reboots,))
|
||||||
|
Loading…
Reference in New Issue
Block a user