Skip to content

Commit

Permalink
Tools: add junit output for autotest
Browse files Browse the repository at this point in the history
  • Loading branch information
khancyr committed Oct 10, 2023
1 parent 88dd813 commit 4d96a13
Show file tree
Hide file tree
Showing 2 changed files with 41 additions and 5 deletions.
9 changes: 7 additions & 2 deletions Tools/autotest/autotest.py
Original file line number Diff line number Diff line change
Expand Up @@ -382,7 +382,7 @@ def run_specific_test(step, *args, **kwargs):
a = Test(a)
print("Got %s" % (a.name))
if a.name == test:
return (tester.autotest(tests=[a], allow_skips=False), tester)
return tester.autotest(tests=[a], allow_skips=False, step_name=step), tester
print("Failed to find test %s on %s" % (test, testname))
sys.exit(1)

Expand Down Expand Up @@ -506,6 +506,7 @@ def run_step(step):
"sup_binaries": supplementary_binaries,
"reset_after_every_test": opts.reset_after_every_test,
"build_opts": copy.copy(build_opts),
"generate_junit": opts.junit,
}
if opts.speedup is not None:
fly_opts["speedup"] = opts.speedup
Expand All @@ -516,7 +517,7 @@ def run_step(step):
global tester
tester = tester_class_map[step](binary, **fly_opts)
# run the test and return its result and the tester itself
return (tester.autotest(), tester)
return tester.autotest(None, step_name=step), tester

# handle "test.Copter.CPUFailsafe" etc:
specific_test_to_run = find_specific_test_to_run(step)
Expand Down Expand Up @@ -884,6 +885,10 @@ def format_epilog(self, formatter):
action='store_true',
default=False,
help='configure with --Werror')
parser.add_option("--junit",
default=False,
action='store_true',
help='Generate Junit XML tests report')

group_build = optparse.OptionGroup(parser, "Build options")
group_build.add_option("--no-configure",
Expand Down
37 changes: 34 additions & 3 deletions Tools/autotest/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
import sys
import time
import traceback
from typing import List

import pexpect
import fnmatch
import operator
Expand Down Expand Up @@ -1466,6 +1468,7 @@ def __init__(self, test):
self.reason = None
self.exception = None
self.debug_filename = None
self.time_elapsed = 0.0
# self.passed = False

def __str__(self):
Expand All @@ -1478,7 +1481,8 @@ def __str__(self):
ret += " (" + str(self.exception) + ")"
if self.debug_filename is not None:
ret += " (see " + self.debug_filename + ")"

if self.time_elapsed is not None:
ret += " (duration " + self.time_elapsed + "s)"
return ret


Expand Down Expand Up @@ -1512,6 +1516,7 @@ def __init__(self,
ubsan_abort=False,
num_aux_imus=0,
dronecan_tests=False,
generate_junit=False,
build_opts={}):

self.start_time = time.time()
Expand Down Expand Up @@ -1540,6 +1545,7 @@ def __init__(self,
self.ubsan_abort = ubsan_abort
self.build_opts = build_opts
self.num_aux_imus = num_aux_imus
self.generate_junit = generate_junit

self.mavproxy = None
self._mavproxy = None # for auto-cleanup on failed tests
Expand Down Expand Up @@ -7918,6 +7924,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout=
passed = False

result = Result(test)
result.time_elapsed = self.test_timings[desc]

ardupilot_alive = False
try:
Expand Down Expand Up @@ -11221,7 +11228,7 @@ def assert_current_onboard_log_contains_message(self, messagetype):
if not self.current_onboard_log_contains_message(messagetype):
raise NotAchievedException("Current onboard log does not contain message %s" % messagetype)

def run_tests(self, tests):
def run_tests(self, tests) -> List[Result]:
"""Autotest vehicle in SITL."""
if self.run_tests_called:
raise ValueError("run_tests called twice")
Expand Down Expand Up @@ -13447,7 +13454,7 @@ def post_tests_announcements(self):
print("Had to force-reset SITL %u times" %
(self.forced_post_test_sitl_reboots,))

def autotest(self, tests=None, allow_skips=True):
def autotest(self, tests=None, allow_skips=True, step_name=None):
"""Autotest used by ArduPilot autotest CI."""
if tests is None:
tests = self.tests()
Expand Down Expand Up @@ -13488,9 +13495,33 @@ def autotest(self, tests=None, allow_skips=True):
print(str(failure))

self.post_tests_announcements()
if self.generate_junit:
if step_name is None:
step_name = "Unknown_step_name"
step_name.replace(".", "_")
self.create_junit_report(step_name, results, skip_list)

return len(self.fail_list) == 0

def create_junit_report(self, test_name: str, results: List[Result], skip_list: list[tuple[Test, dict[str, str]]]) -> None:
"""Generate Junit report from the autotest results"""
from junitparser import TestCase, TestSuite, JUnitXml, Skipped, Error
suite = TestSuite("ArduPilot Autotest")
suite.add_property("Autotest name", f"{test_name}")
for result in results:
case = TestCase(f"{result.test.name}", f"{result.test.description}", result.time_elapsed)
if not result.passed:
case.result = [Error(f"Failure : {result.reason}", f"{result.exception}")]
suite.add_testcase(case)
for skipped in skip_list:
(test, reason) = skipped
case = TestCase(f"{test.name}", f"{test.function}")
case.result = [Skipped(f"Skipped : {reason}")]
# Add suite to JunitXml
xml = JUnitXml()
xml.add_testsuite(suite)
xml.write(f"autotest_result_{test_name}_junit.xml")

def mavfft_fttd(self, sensor_type, sensor_instance, since, until):
'''display fft for raw ACC data in current logfile'''

Expand Down

0 comments on commit 4d96a13

Please sign in to comment.