auto est: modular tests and unit testing with Junit.xml output for jenkins

autotest: unit testing for jenkins
- parameterized unit testing
- modular python test modules
- test groups by directory
- select tests individual or by group
- skip tests individually or by group

arducopter.py: parameterized several functions to allow throttle settings and timeouts

test modules: extracted and copied 8 tests from Tridge's autotest into modules

junit.xml: xml template for unit test reporting to jenkins
This commit is contained in:
Andreas M. Antonopoulos 2012-07-05 23:48:50 -07:00
parent f501503eb0
commit 29338fbf7b
11 changed files with 660 additions and 42 deletions

View File

@ -0,0 +1,62 @@
import arducopter
import util, pexpect, sys, time, math, shutil, os
from common import *
import mavutil, mavwp, random
def unit_test(mavproxy, mav):
'''A scripted flight plan for testing AP_Limits'''
time.sleep(5)
print "# Setting AP_Limits parameters"
mavproxy.send('param set LIM_ENABLED 1\n')
mavproxy.send('param set LIM_REQUIRED 0\n')
mavproxy.send('param set LIM_DEBUG 1\n')
mavproxy.send('param set LIM_SAFETIME 1\n')
mavproxy.send('param set LIM_ALT_ON 1\n')
mavproxy.send('param set LIM_ALT_REQ 0\n')
mavproxy.send('param set LIM_ALT_MIN 0\n')
mavproxy.send('param set LIM_ALT_MAX 50\n')
mavproxy.send('param set LIM_FNC_ON 0\n')
mavproxy.send('param set LIM_FNC_REQ 0\n')
mavproxy.send('param set LIM_FNC_SMPL 1\n')
mavproxy.send('param set LIM_FNC_RAD 50\n')
time.sleep(5)
print "# Listing AP_Limits parameters"
mavproxy.send('param show LIM*\n')
if (
arducopter.calibrate_level(mavproxy, mav) and
arducopter.arm_motors(mavproxy, mav) and
arducopter.takeoff(mavproxy,mav, alt_min=30, takeoff_throttle=1510) and
arducopter.hover(mavproxy, mav, hover_throttle=1500)
):
# Trigger for ALT_MAX
climb_rate = 0
previous_alt = 0
timeout = 30
# Do Not Exceed altitude
alt_dne = 55
tstart = time.time()
mavproxy.send('rc 3 1550\n')
while (time.time() < tstart + timeout):
m = mav.recv_match(type='VFR_HUD', blocking=True)
climb_rate = m.alt - previous_alt
previous_alt = m.alt
print("Trigger Altitude Limit: Cur:%u, climb_rate: %u" % (m.alt, climb_rate))
if abs(climb_rate) > 0:
tstart = time.time();
if (mav.recv_match(condition='MAV.flightmode=="GUIDED"', blocking=False) != None):
print "Triggered!"
return True
if m.alt >= alt_dne :
print("Altitude Exceeded")
return False
return False
return False

View File

@ -0,0 +1,13 @@
import arducopter
def unit_test(mavproxy, mav):
'''A scripted flight plan'''
if (
arducopter.calibrate_level(mavproxy, mav) and
arducopter.arm_motors(mavproxy, mav) and
arducopter.takeoff(mavproxy,mav, alt_min=30, takeoff_throttle=1510) and
arducopter.hover(mavproxy,mav, hover_throttle=1300) and
arducopter.loiter(mavproxy, mav, holdtime=45, maxaltchange=20)): # 45 second loiter
return True
return False

View File

@ -0,0 +1,13 @@
import arducopter
def unit_test(mavproxy, mav):
'''A scripted flight plan'''
if (
arducopter.calibrate_level(mavproxy, mav) and
arducopter.arm_motors(mavproxy, mav) and
arducopter.takeoff(mavproxy,mav, alt_min=80, takeoff_throttle=1510) and
arducopter.hover(mavproxy,mav, hover_throttle=1300) and
arducopter.fly_RTL(mavproxy, mav, side=80, timeout=80)):
return True
return False

View File

@ -0,0 +1,14 @@
import arducopter
def unit_test(mavproxy, mav):
'''A scripted flight plan'''
if (
arducopter.calibrate_level(mavproxy, mav) and
arducopter.arm_motors(mavproxy, mav) and
arducopter.takeoff(mavproxy,mav, alt_min=30, takeoff_throttle=1510) and
arducopter.change_alt(mavproxy, mav, alt_min=60) and
arducopter.change_alt(mavproxy, mav, alt_min=20)
):
return True
return False

View File

@ -0,0 +1,14 @@
import arducopter
def unit_test(mavproxy, mav):
'''A scripted flight plan'''
if (
arducopter.calibrate_level(mavproxy, mav) and
arducopter.arm_motors(mavproxy, mav) and
arducopter.takeoff(mavproxy,mav, alt_min=80, takeoff_throttle=1510) and
arducopter.hover(mavproxy,mav, hover_throttle=1300) and
arducopter.fly_failsafe(mavproxy, mav, side=80, timeout=120)
):
return True
return False

View File

@ -0,0 +1,8 @@
import arducopter
def unit_test(mavproxy, mav):
'''A scripted flight plan'''
if (arducopter.calibrate_level(mavproxy, mav)):
return True
return False

View File

@ -0,0 +1,11 @@
import arducopter
def unit_test(mavproxy, mav):
'''A scripted flight plan'''
if (
arducopter.calibrate_level(mavproxy, mav) and
arducopter.arm_motors(mavproxy, mav) and
arducopter.disarm_motors(mavproxy,mav)):
return True
return False

View File

@ -0,0 +1,11 @@
import arducopter
def unit_test(mavproxy, mav):
'''A scripted flight plan'''
if (
arducopter.calibrate_level(mavproxy, mav) and
arducopter.arm_motors(mavproxy, mav) and
arducopter.takeoff(mavproxy,mav, alt_min=30, takeoff_throttle=1510)):
return True
return False

View File

@ -14,8 +14,8 @@ HOME=mavutil.location(-35.362938,149.165085,584,270)
homeloc = None
num_wp = 0
def hover(mavproxy, mav):
mavproxy.send('rc 3 1395\n')
def hover(mavproxy, mav, hover_throttle=1300):
mavproxy.send('rc 3 %u\n' % hover_throttle)
return True
def calibrate_level(mavproxy, mav):
@ -49,11 +49,11 @@ def disarm_motors(mavproxy, mav):
return True
def takeoff(mavproxy, mav, alt_min = 30):
def takeoff(mavproxy, mav, alt_min = 30, takeoff_throttle=1510):
'''takeoff get to 30m altitude'''
mavproxy.send('switch 6\n') # stabilize mode
wait_mode(mav, 'STABILIZE')
mavproxy.send('rc 3 1510\n')
mavproxy.send('rc 3 %u\n' % takeoff_throttle)
m = mav.recv_match(type='VFR_HUD', blocking=True)
if (m.alt < alt_min):
wait_altitude(mav, alt_min, (alt_min + 5))
@ -84,16 +84,16 @@ def loiter(mavproxy, mav, holdtime=60, maxaltchange=20):
print("Loiter FAILED")
return False
def change_alt(mavproxy, mav, alt_min):
def change_alt(mavproxy, mav, alt_min, climb_throttle=1920, descend_throttle=1120):
'''change altitude'''
m = mav.recv_match(type='VFR_HUD', blocking=True)
if(m.alt < alt_min):
print("Rise to alt:%u from %u" % (alt_min, m.alt))
mavproxy.send('rc 3 1920\n')
mavproxy.send('rc 3 %u\n' % climb_throttle)
wait_altitude(mav, alt_min, (alt_min + 5))
else:
print("Lower to alt:%u from %u" % (alt_min, m.alt))
mavproxy.send('rc 3 1120\n')
mavproxy.send('rc 3 %u\n' % descend_throttle)
wait_altitude(mav, (alt_min -5), alt_min)
hover(mavproxy, mav)
return True
@ -155,7 +155,7 @@ def fly_square(mavproxy, mav, side=50, timeout=120):
return not failed
def fly_RTL(mavproxy, mav, side=60):
def fly_RTL(mavproxy, mav, side=60, timeout=250):
'''Fly, return, land'''
mavproxy.send('switch 6\n')
wait_mode(mav, 'STABILIZE')
@ -171,7 +171,7 @@ def fly_RTL(mavproxy, mav, side=60):
print("# Enter RTL")
mavproxy.send('switch 3\n')
tstart = time.time()
while time.time() < tstart + 200:
while time.time() < tstart + timeout:
m = mav.recv_match(type='VFR_HUD', blocking=True)
pos = mav.location()
#delta = get_distance(start, pos)
@ -180,7 +180,7 @@ def fly_RTL(mavproxy, mav, side=60):
return True
return True
def fly_failsafe(mavproxy, mav, side=60):
def fly_failsafe(mavproxy, mav, side=60, timeout=120):
'''Fly, Failsafe, return, land'''
mavproxy.send('switch 6\n')
wait_mode(mav, 'STABILIZE')
@ -196,7 +196,7 @@ def fly_failsafe(mavproxy, mav, side=60):
print("# Enter Failsafe")
mavproxy.send('rc 3 900\n')
tstart = time.time()
while time.time() < tstart + 250:
while time.time() < tstart + timeout:
m = mav.recv_match(type='VFR_HUD', blocking=True)
pos = mav.location()
home_distance = get_distance(HOME, pos)
@ -205,7 +205,7 @@ def fly_failsafe(mavproxy, mav, side=60):
print("Reached failsafe home OK")
mavproxy.send('rc 3 1100\n')
return True
print("Failed to land on failsafe RTL - timed out after 120 seconds")
print("Failed to land on failsafe RTL - timed out after %u seconds" % timeout)
return False
@ -548,33 +548,3 @@ def fly_ArduCopter(viewerip=None):
#! mavproxy.send('rc 2 1390\n')
#! #adjust till the rate is 0;
#!
#! mavproxy.send('rc 4 1610\n')
#! if not wait_heading(mav, 0):
#! return False
#! mavproxy.send('rc 4 1500\n')
#!
#! mavproxy.send('rc 2 1455\n')
#! #adjust till the rate is 0;
#! pitch_test = 1455
#! roll_test = 1500
#! old_lat = 0
#! old_lon = 0
#!
#! while(1):
#! pos = mav.location()
#! tmp = (pos.lat *10e7) - (old_lat *10e7)
#! print("tmp %d " % tmp)
#! if(tmp > 0 ):
#! print("higher tmp %d " % (tmp))
#! pitch_test += 1
#! if(tmp < 0 ):
#! print("lower tmp %d " % (tmp))
#! pitch_test -= 1
#! mavproxy.send('rc 2 %u\n' % math.floor(pitch_test))
#! old_lat = pos.lat
#! #old_lon = pos.lon

View File

@ -0,0 +1,494 @@
#!/usr/bin/env python
# APM automatic test suite
# Andrew Tridgell, October 2011
import pexpect, os, sys, shutil, atexit
sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), 'pysim'))
sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..', '..', '..', 'mavlink', 'pymavlink'))
import optparse, fnmatch, time, glob, traceback, signal, util, time, math, common
from common import *
import mavutil, mavwp, random
import arduplane, arducopter
# Defaults
HOME=mavutil.location(-35.362938,149.165085,584,270)
# ArduCopter defaults
FRAME='+'
homeloc = None
num_wp = 0
# get location of scripts
testdir=os.path.dirname(os.path.realpath(__file__))
os.environ['PYTHONUNBUFFERED'] = '1'
os.putenv('TMPDIR', util.reltopdir('tmp'))
def get_default_params(atype):
'''get default parameters'''
sil = util.start_SIL(atype, wipe=True)
mavproxy = util.start_MAVProxy_SIL(atype)
print("Dumping defaults")
idx = mavproxy.expect(['Please Run Setup', 'Saved [0-9]+ parameters to (\S+)'])
if idx == 0:
# we need to restart it after eeprom erase
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
sil = util.start_SIL(atype)
mavproxy = util.start_MAVProxy_SIL(atype)
idx = mavproxy.expect('Saved [0-9]+ parameters to (\S+)')
parmfile = mavproxy.match.group(1)
dest = util.reltopdir('../buildlogs/%s.defaults.txt' % atype)
shutil.copy(parmfile, dest)
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
print("Saved defaults for %s to %s" % (atype, dest))
return True
def dump_logs(atype):
'''dump DataFlash logs'''
print("Dumping logs for %s" % atype)
sil = util.start_SIL(atype, CLI=True)
logfile = util.reltopdir('../buildlogs/%s.flashlog' % atype)
log = open(logfile, mode='w')
mavproxy = util.start_MAVProxy_SIL(atype, setup=True, logfile=log)
mavproxy.send('\n\n\n')
print("navigating menus")
mavproxy.expect(']')
mavproxy.send("logs\n")
mavproxy.expect("logs enabled:")
lognums = []
i = mavproxy.expect(["No logs", "(\d+) logs"])
if i == 0:
numlogs = 0
else:
numlogs = int(mavproxy.match.group(1))
for i in range(numlogs):
mavproxy.expect("Log (\d+),")
lognums.append(int(mavproxy.match.group(1)))
mavproxy.expect("Log]")
for i in range(numlogs):
print("Dumping log %u (i=%u)" % (lognums[i], i))
mavproxy.send("dump %u\n" % lognums[i])
mavproxy.expect("logs enabled:", timeout=120)
mavproxy.expect("Log]")
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
log.close()
print("Saved log for %s to %s" % (atype, logfile))
return True
def convert_gpx():
'''convert any mavlog files to GPX and KML'''
import glob
mavlog = glob.glob(util.reltopdir("../buildlogs/*.mavlog"))
for m in mavlog:
util.run_cmd(util.reltopdir("../pymavlink/examples/mavtogpx.py") + " --nofixcheck " + m)
gpx = m + '.gpx'
kml = m + '.kml'
util.run_cmd('gpsbabel -i gpx -f %s -o kml,units=m,floating=1,extrude=1 -F %s' % (gpx, kml), checkfail=False)
util.run_cmd('zip %s.kmz %s.kml' % (m, m), checkfail=False)
return True
def test_prerequesites():
'''check we have the right directories and tools to run tests'''
print("Testing prerequesites")
util.mkdir_p(util.reltopdir('../buildlogs'))
return True
def alarm_handler(signum, frame):
'''handle test timeout'''
global results, opts
try:
results.add('TIMEOUT', '<span class="failed-text">FAILED</span>', opts.timeout)
util.pexpect_close_all()
results.addfile('Full Logs', 'autotest-output.txt')
results.addglob('DataFlash Log', '*.flashlog')
results.addglob("MAVLink log", '*.mavlog')
results.addfile('ArduPlane build log', 'ArduPlane.txt')
results.addfile('ArduPlane defaults', 'ArduPlane.defaults.txt')
results.addfile('ArduCopter build log', 'ArduCopter.txt')
results.addfile('ArduCopter defaults', 'ArduCopter.defaults.txt')
write_webresults(results)
os.killpg(0, signal.SIGKILL)
except Exception:
pass
sys.exit(1)
import arducopter, arduplane
class Test(object):
''' unit test class '''
def __init__(self, name, path, test):
self.name = name
self.path = path
self.test = test
self.result = False
self.log = ''
def fly_ArduCopter_scripted(testname):
'''fly ArduCopter in SIL
'''
global homeloc
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_multicopter.py') + ' --frame=%s --rate=400 --home=%f,%f,%u,%u' % (
FRAME, HOME.lat, HOME.lng, HOME.alt, HOME.heading)
sim_cmd += ' --wind=6,45,.3'
sil = util.start_SIL('ArduCopter', wipe=True)
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter')
mavproxy.expect('Received [0-9]+ parameters')
# setup test parameters
mavproxy.send('param set SYSID_THISMAV %u\n' % random.randint(100, 200))
mavproxy.send("param load %s/ArduCopter.parm\n" % testdir)
mavproxy.expect('Loaded [0-9]+ parameters')
# reboot with new parameters
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
sil = util.start_SIL('ArduCopter', height=HOME.alt)
sim = pexpect.spawn(sim_cmd, logfile=sys.stdout, timeout=10)
sim.delaybeforesend = 0
util.pexpect_autoclose(sim)
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5'
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options=options)
mavproxy.expect('Logging to (\S+)')
logfile = mavproxy.match.group(1)
print("LOGFILE %s" % logfile)
buildlog = util.reltopdir("../buildlogs/ArduCopter-test.mavlog")
print("buildlog=%s" % buildlog)
if os.path.exists(buildlog):
os.unlink(buildlog)
os.link(logfile, buildlog)
# the received parameters can come before or after the ready to fly message
mavproxy.expect(['Received [0-9]+ parameters', 'Ready to FLY'])
mavproxy.expect(['Received [0-9]+ parameters', 'Ready to FLY'])
util.expect_setup_callback(mavproxy, arducopter.expect_callback)
expect_list_clear()
expect_list_extend([sim, sil, mavproxy])
# get a mavlink connection going
try:
mav = mavutil.mavlink_connection('127.0.0.1:19550', robust_parsing=True)
except Exception, msg:
print("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
raise
mav.message_hooks.append(message_hook)
mav.idle_hooks.append(idle_hook)
failed = False
e = 'None'
try:
mav.wait_heartbeat()
arducopter.setup_rc(mavproxy)
homeloc = mav.location()
print("# Executing test - " + testname)
if not test_suite[testname].test(mavproxy, mav):
print("Test script failed")
failed = True
except pexpect.TIMEOUT, e:
failed = True
mav.close()
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
util.pexpect_close(sim)
if os.path.exists('ArduCopter-valgrind.log'):
os.chmod('ArduCopter-valgrind.log', 0644)
shutil.copy("ArduCopter-valgrind.log", util.reltopdir("../buildlogs/ArduCopter-valgrind.log"))
if failed:
print("FAILED: %s" % e)
return False
return True
class TestResult(object):
'''test result class'''
def __init__(self, name, result="", elapsed=0):
self.name = name
self.success = False
self.result = result
self.elapsed = "%1.f" % elapsed
class TestFile(object):
'''test result file'''
def __init__(self, name, fname):
self.name = name
self.fname = fname
class TestResults(object):
'''test results class'''
def __init__(self):
self.date = time.asctime()
self.isotime = time.strftime("%Y-%m-%dT%H:%M:%S")
self.githash = util.run_cmd('git rev-parse HEAD', output=True, dir=util.reltopdir('.')).strip()
self.tests = []
self.files = []
def add(self, name, result, elapsed):
'''add a result'''
self.tests.append(TestResult(name, result, elapsed))
def addfile(self, name, fname):
'''add a result file'''
self.files.append(TestFile(name, fname))
def addglob(self, name, pattern):
'''add a set of files'''
import glob
for f in glob.glob(util.reltopdir('../buildlogs/%s' % pattern)):
self.addfile(name, os.path.basename(f))
def write_XMLresults(atype, results):
'''write XML JUnit results'''
sys.path.insert(0, os.path.join(util.reltopdir("../pymavlink/generator")))
import mavtemplate
t = mavtemplate.MAVTemplate()
for x in glob.glob(util.reltopdir('Tools/autotest/junit.xml')):
junit_xml = util.loadfile(x)
f = open(util.reltopdir("../buildlogs/%s-%s" % (atype, os.path.basename(x))), mode='w')
t.write(f, junit_xml, results)
f.close()
def write_webresults(results):
'''write webpage results'''
sys.path.insert(0, os.path.join(util.reltopdir("../pymavlink/generator")))
import mavtemplate
t = mavtemplate.MAVTemplate()
for h in glob.glob(util.reltopdir('Tools/autotest/web/*.html')):
html = util.loadfile(h)
f = open(util.reltopdir("../buildlogs/%s" % os.path.basename(h)), mode='w')
t.write(f, html, results)
f.close()
for f in glob.glob(util.reltopdir('Tools/autotest/web/*.png')):
shutil.copy(f, util.reltopdir('../buildlogs/%s' % os.path.basename(f)))
results = TestResults()
unit_test_results = TestResults()
def run_tests(tests):
'''run a list of tests'''
global results, unit_test_results
passed = True
failed = []
for testname in tests:
util.pexpect_close_all()
testcase = TestResult(testname)
testcase.success = False
t1 = time.time()
print(">>>> RUNNING test: %s at %s" % (testname, time.asctime()))
try:
if not fly_ArduCopter_scripted(testname):
print(">>>> FAILED test: %s at %s" % (testname, time.asctime()))
passed = False
testcase.elapsed = "%.1f" % (time.time() - t1)
testcase.result = '''
<testcase classname="ardupilot-mega-autotest"
name=\"%s\" time=\"%s\">
<failure type=\"test failure\">
%s
</failure>
</testcase>
''' % (testcase.name, testcase.elapsed, "failed")
unit_test_results.tests.append(testcase)
print testcase.result
failed.append(testname)
continue
except Exception, msg:
testcase.elapsed = "%.1f" % (time.time() - t1)
passed = False
print(">>>> FAILED test: %s at %s (%s)" % (testname, time.asctime(), msg))
traceback.print_exc(file=sys.stdout)
testcase.result = '''
<testcase classname="ardupilot-mega-autotest"
name=\"%s\" time=\"%s\">
<error type=\"Test error\">
%s
</error>
</testcase>
''' % (testcase.name, testcase.elapsed, traceback.format_exc() )
print testcase.result
unit_test_results.tests.append(testcase)
failed.append(testcase.name)
continue
#success
testcase.elapsed = "%.1f" % (time.time() - t1)
testcase.success = True
testcase.result = '''
<testcase classname="ardupilot-mega-autotest"
name=\"%s\" time=\"%s\">
</testcase>
''' % (testcase.name, testcase.elapsed )
unit_test_results.tests.append(testcase)
print(">>>> PASSED test: %s at %s" % (testname, time.asctime()))
print testcase.result
dump_logs('ArduCopter')
convert_gpx()
if not passed:
print("FAILED %u tests: %s" % (len(failed), failed))
util.pexpect_close_all()
results.addglob("Google Earth track", '*.kmz')
results.addfile('Full Logs', 'autotest-output.txt')
results.addglob('DataFlash Log', '*.flashlog')
results.addglob("MAVLink log", '*.mavlog')
results.addglob("GPX track", '*.gpx')
unit_test_results.num_tests = len(results.tests)
unit_test_results.num_failures = len(failed)
write_XMLresults("ArduCopter", unit_test_results)
write_webresults(results)
# individual test results in XML. Always True
return True
############## main program #############
parser = optparse.OptionParser(sys.argv[0])
parser.add_option("--list", action='store_true', default=False, help='list the available tests (comma separated, can be used as TESTLIST')
parser.add_option("--run", type='string', default='', metavar="TESTLIST", help='list of tests to run (comma separated)' )
parser.add_option("--rungroup", type='string', default='', metavar="TESTLIST", help='list of test groups to run (comma separated)' )
parser.add_option("--skip", type='string', default='', metavar="TESTLIST", help='list of tests to skip (comma separated)')
parser.add_option("--skipgroup", type='string', default='', metavar="TESTLIST", help='list of test groups to skip (comma separated)')
opts, args = parser.parse_args()
#### Load test modules ####
print '>>>>>> Loading ArduCopter TEST MODULES'
import glob
test_suite = {}
test_groups = {}
test_base_path = 'APM/Tools/autotest/apm_unit_tests/'
print test_base_path
print os.path.dirname(os.path.realpath(__file__))
test_group_names = glob.glob(test_base_path+'*')
for gname in test_group_names:
sys.path.insert(0, gname)
gname = os.path.basename(gname)
gtests = glob.glob(test_base_path + gname + '/*.py')
if gtests:
test_groups[gname] = []
for tmodule in gtests:
tname = os.path.basename(tmodule)
if (tname.endswith('.py')):
tname = (tname[:-3]).strip() # chop off the .py
test_groups[gname].append(tname)
test_suite[tname.strip()] = tmodule
alltests = test_suite.keys()
allgroups = test_groups.keys()
if (len(alltests) == 0):
print "Error: no test modules selected"
exit(1)
if opts.list:
print "\n\nFound %s modules in %s groups" % ((len(alltests), len(allgroups)))
print "\n\nAvailable tests: "
print ', '.join(alltests)
print "\n\nAvailable groups: "
for g in allgroups:
print g + " --- " + ','.join(test_groups[g])
if opts.rungroup:
for group in opts.rungroup.split(','):
opts.run += ','.join(test_groups[group])
if opts.skipgroup:
for group in opts.skipgroup.split(','):
opts.skip += ','.join(test_groups[group])
runtests = []
print "Selected: " + opts.run
print "Skipping: " + opts.skip
if opts.run:
for runtest in opts.run.split(','):
runtests.append(runtest.strip())
print "Adding test - %s" % runtest
else:
runtests = alltests
finaltests = []
if opts.skip:
skiptests = opts.skip.split(',')
print "Skipping tests: " + ','.join(skiptests)
for runtest in runtests:
if runtest not in skiptests:
finaltests.append(runtest)
else:
print "Skipping test - %s" % runtest
else:
finaltests = runtests
if (len(finaltests) > 0):
print "\n\n***\nLoading selected tests: " + ','.join(finaltests)
else:
print "Error: no test modules selected"
exit(1)
for tname in finaltests:
print "Loading ArduCopter test module: " + tname
try:
mpath = test_suite[tname]
m = __import__ (tname)
unit_test = getattr(m,'unit_test')
test_module = Test(tname, mpath, unit_test)
test_suite[tname] = test_module
except Exception:
raise
print '>>>>>> Running TEST MODULES'
atexit.register(util.pexpect_close_all)
try:
run_tests(finaltests)
sys.exit(0)
except KeyboardInterrupt:
util.pexpect_close_all()
sys.exit(1)
except Exception:
# make sure we kill off any children
util.pexpect_close_all()
raise

8
Tools/autotest/junit.xml Normal file
View File

@ -0,0 +1,8 @@
<testsuites>
<testsuite>
${{tests:
${result}
}}
</testsuite>
</testsuites>