Tools: autotest.py: flake8 compliance

Also fixed a bug where CalledProcessError has not been imported
This commit is contained in:
Peter Barker 2018-07-04 10:51:22 +10:00 committed by Peter Barker
parent 48d00de030
commit 0ae82751b8
1 changed files with 171 additions and 92 deletions

View File

@ -11,23 +11,26 @@ import optparse
import os
import shutil
import signal
import subprocess
import sys
import time
import traceback
from apmrover2 import *
from arducopter import *
from quadplane import *
from arduplane import *
from ardusub import *
import apmrover2
import arducopter
import arduplane
import ardusub
import quadplane
from pysim import util
from pymavlink import mavutil
from pymavlink.generator import mavtemplate
def buildlogs_dirpath():
return os.getenv("BUILDLOGS", util.reltopdir("../buildlogs"))
def buildlogs_path(path):
'''return a string representing path in the buildlogs directory'''
bits = [buildlogs_dirpath()]
@ -37,21 +40,30 @@ def buildlogs_path(path):
bits.append(path)
return os.path.join(*bits)
def get_default_params(atype, binary):
"""Get default parameters."""
# use rover simulator so SITL is not starved of input
HOME = mavutil.location(40.071374969556928, -105.22978898137808, 1583.702759, 246)
HOME = mavutil.location(40.071374969556928,
-105.22978898137808,
1583.702759,
246)
if "plane" in binary or "rover" in binary:
frame = "rover"
else:
frame = "+"
home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
sitl = util.start_SITL(binary, wipe=True, model=frame, home=home, speedup=10, unhide_parameters=True)
sitl = util.start_SITL(binary,
wipe=True,
model=frame,
home=home,
speedup=10,
unhide_parameters=True)
mavproxy = util.start_MAVProxy_SITL(atype)
print("Dumping defaults")
idx = mavproxy.expect(['Please Run Setup', 'Saved [0-9]+ parameters to (\S+)'])
idx = mavproxy.expect(['Saved [0-9]+ parameters to (\S+)'])
if idx == 0:
# we need to restart it after eeprom erase
util.pexpect_close(mavproxy)
@ -68,10 +80,14 @@ def get_default_params(atype, binary):
return True
def build_all_filepath():
return util.reltopdir('Tools/scripts/build_all.sh')
def build_all():
"""Run the build_all.sh script."""
print("Running build_all.sh")
if util.run_cmd(util.reltopdir('Tools/scripts/build_all.sh'), directory=util.reltopdir('.')) != 0:
if util.run_cmd(build_all_filepath, directory=util.reltopdir('.')) != 0:
print("Failed build_all.sh")
return False
return True
@ -80,7 +96,8 @@ def build_all():
def build_binaries():
"""Run the build_binaries.py script."""
print("Running build_binaries.py")
# copy the script as it changes git branch, which can change the script while running
# copy the script as it changes git branch, which can change the
# script while running
orig = util.reltopdir('Tools/scripts/build_binaries.py')
copy = util.reltopdir('./build_binaries.py')
shutil.copy2(orig, copy)
@ -99,7 +116,8 @@ def build_binaries():
def build_devrelease():
"""Run the build_devrelease.sh script."""
print("Running build_devrelease.sh")
# copy the script as it changes git branch, which can change the script while running
# copy the script as it changes git branch, which can change the
# script while running
orig = util.reltopdir('Tools/scripts/build_devrelease.sh')
copy = util.reltopdir('./build_devrelease.sh')
shutil.copy2(orig, copy)
@ -124,31 +142,50 @@ def build_examples():
return True
def param_parse_filepath():
return util.reltopdir('Tools/autotest/param_metadata/param_parse.py')
def all_vehicles():
return ('ArduPlane',
'ArduCopter',
'APMrover2',
'AntennaTracker',
'ArduSub')
def build_parameters():
"""Run the param_parse.py script."""
print("Running param_parse.py")
for vehicle in 'ArduPlane', 'ArduCopter', 'ArduSub', 'APMrover2', 'AntennaTracker':
if util.run_cmd([util.reltopdir('Tools/autotest/param_metadata/param_parse.py'), '--vehicle', vehicle], directory=util.reltopdir('.')) != 0:
for vehicle in all_vehicles():
if util.run_cmd([param_parse_filepath(), '--vehicle', vehicle],
directory=util.reltopdir('.')) != 0:
print("Failed param_parse.py (%s)" % vehicle)
return False
return True
def mavtogpx_filepath():
return util.reltopdir("modules/mavlink/pymavlink/tools/mavtogpx.py")
def convert_gpx():
"""Convert any tlog files to GPX and KML."""
mavlog = glob.glob(buildlogs_path("*.tlog"))
passed = True
for m in mavlog:
util.run_cmd(util.reltopdir("modules/mavlink/pymavlink/tools/mavtogpx.py") + " --nofixcheck " + m)
util.run_cmd(mavtogpx_filepath() + " --nofixcheck " + m)
gpx = m + '.gpx'
kml = m + '.kml'
try:
util.run_cmd('gpsbabel -i gpx -f %s -o kml,units=m,floating=1,extrude=1 -F %s' % (gpx, kml))
except CalledProcessError as e:
util.run_cmd('gpsbabel -i gpx -f %s '
'-o kml,units=m,floating=1,extrude=1 -F %s' %
(gpx, kml))
except subprocess.CalledProcessError as e:
passed = False
try:
util.run_cmd('zip %s.kmz %s.kml' % (m, m))
except CalledProcessError as e:
except subprocess.CalledProcessError as e:
passed = False
util.run_cmd("mavflightview.py --imagefile=%s.png %s" % (m, m))
return passed
@ -165,7 +202,9 @@ def alarm_handler(signum, frame):
"""Handle test timeout."""
global results, opts
try:
results.add('TIMEOUT', '<span class="failed-text">FAILED</span>', opts.timeout)
results.add('TIMEOUT',
'<span class="failed-text">FAILED</span>',
opts.timeout)
util.pexpect_close_all()
convert_gpx()
write_fullresults()
@ -174,6 +213,7 @@ def alarm_handler(signum, frame):
pass
sys.exit(1)
def should_run_step(step):
"""See if a step should be skipped."""
for skip in skipsteps:
@ -181,16 +221,18 @@ def should_run_step(step):
return False
return True
__bin_names = {
"ArduCopter" : "arducopter",
"ArduPlane" : "arduplane",
"APMrover2" : "ardurover",
"AntennaTracker" : "antennatracker",
"CopterAVC" : "arducopter-heli",
"QuadPlane" : "arduplane",
"ArduSub" : "ardusub"
"ArduCopter": "arducopter",
"ArduPlane": "arduplane",
"APMrover2": "ardurover",
"AntennaTracker": "antennatracker",
"CopterAVC": "arducopter-heli",
"QuadPlane": "arduplane",
"ArduSub": "ardusub"
}
def binary_path(step, debug=False):
try:
vehicle = step.split(".")[1]
@ -203,9 +245,10 @@ def binary_path(step, debug=False):
# cope with builds that don't have a specific binary
return None
binary_basedir = "sitl"
binary = util.reltopdir(os.path.join('build', binary_basedir, 'bin', binary_name))
binary = util.reltopdir(os.path.join('build',
'sitl',
'bin',
binary_name))
if not os.path.exists(binary):
if os.path.exists(binary + ".exe"):
binary += ".exe"
@ -270,28 +313,32 @@ def run_step(step):
fly_opts["speedup"] = opts.speedup
if step == 'fly.ArduCopter':
arducopter = AutoTestCopter(binary, frame=opts.frame, **fly_opts)
return arducopter.autotest()
tester = arducopter.AutoTestCopter(binary,
frame=opts.frame,
**fly_opts)
return tester.autotest()
if step == 'fly.CopterAVC':
arducopter = AutoTestCopter(binary, **fly_opts)
return arducopter.autotest_heli()
tester = arducopter.AutoTestCopter(binary, **fly_opts)
return tester.autotest_heli()
if step == 'fly.ArduPlane':
arduplane = AutoTestPlane(binary, **fly_opts)
return arduplane.autotest()
tester = arduplane.AutoTestPlane(binary, **fly_opts)
return tester.autotest()
if step == 'fly.QuadPlane':
quadplane = AutoTestQuadPlane(binary, **fly_opts)
return quadplane.autotest()
tester = quadplane.AutoTestQuadPlane(binary, **fly_opts)
return tester.autotest()
if step == 'drive.APMrover2':
apmrover2 = AutoTestRover(binary, frame=opts.frame, **fly_opts)
return apmrover2.autotest()
tester = apmrover2.AutoTestRover(binary,
frame=opts.frame,
**fly_opts)
return tester.autotest()
if step == 'dive.ArduSub':
ardusub = AutoTestSub(binary, **fly_opts)
return ardusub.autotest()
tester = ardusub.AutoTestSub(binary, **fly_opts)
return tester.autotest()
if step == 'build.All':
return build_all()
@ -333,7 +380,9 @@ class TestResults(object):
"""Test results class."""
def __init__(self):
self.date = time.asctime()
self.githash = util.run_cmd('git rev-parse HEAD', output=True, directory=util.reltopdir('.')).strip()
self.githash = util.run_cmd('git rev-parse HEAD',
output=True,
directory=util.reltopdir('.')).strip()
self.tests = []
self.files = []
self.images = []
@ -383,17 +432,15 @@ def write_fullresults():
results.addglob("GPX track", '*.gpx')
# results common to all vehicles:
vehicle_files = [ ('{vehicle} build log', '{vehicle}.txt'),
('{vehicle} code size', '{vehicle}.sizes.txt'),
('{vehicle} stack sizes', '{vehicle}.framesizes.txt'),
('{vehicle} defaults', '{vehicle}-defaults.parm'),
('{vehicle} core', '{vehicle}.core'),
('{vehicle} ELF', '{vehicle}.elf'),
]
vehicle_globs = [('{vehicle} log', '{vehicle}-*.BIN'),
]
for vehicle in 'ArduPlane','ArduCopter','APMrover2','AntennaTracker', 'ArduSub':
subs = { 'vehicle': vehicle }
vehicle_files = [('{vehicle} build log', '{vehicle}.txt'),
('{vehicle} code size', '{vehicle}.sizes.txt'),
('{vehicle} stack sizes', '{vehicle}.framesizes.txt'),
('{vehicle} defaults', '{vehicle}-defaults.parm'),
('{vehicle} core', '{vehicle}.core'),
('{vehicle} ELF', '{vehicle}.elf'), ]
vehicle_globs = [('{vehicle} log', '{vehicle}-*.BIN'), ]
for vehicle in all_vehicles():
subs = {'vehicle': vehicle}
for vehicle_file in vehicle_files:
description = vehicle_file[0].format(**subs)
filename = vehicle_file[1].format(**subs)
@ -415,6 +462,7 @@ def write_fullresults():
write_webresults(results)
def check_logs(step):
"""Check for log files from a step."""
print("check step: ", step)
@ -442,6 +490,7 @@ def check_logs(step):
except Exception:
print("Unable to save binary")
def run_tests(steps):
"""Run a list of steps."""
global results
@ -455,20 +504,25 @@ def run_tests(steps):
print(">>>> RUNNING STEP: %s at %s" % (step, time.asctime()))
try:
if run_step(step):
results.add(step, '<span class="passed-text">PASSED</span>', time.time() - t1)
results.add(step, '<span class="passed-text">PASSED</span>',
time.time() - t1)
print(">>>> PASSED STEP: %s at %s" % (step, time.asctime()))
check_logs(step)
else:
print(">>>> FAILED STEP: %s at %s" % (step, time.asctime()))
passed = False
failed.append(step)
results.add(step, '<span class="failed-text">FAILED</span>', time.time() - t1)
results.add(step, '<span class="failed-text">FAILED</span>',
time.time() - t1)
except Exception as msg:
passed = False
failed.append(step)
print(">>>> FAILED STEP: %s at %s (%s)" % (step, time.asctime(), msg))
print(">>>> FAILED STEP: %s at %s (%s)" %
(step, time.asctime(), msg))
traceback.print_exc(file=sys.stdout)
results.add(step, '<span class="failed-text">FAILED</span>', time.time() - t1)
results.add(step,
'<span class="failed-text">FAILED</span>',
time.time() - t1)
check_logs(step)
if not passed:
print("FAILED %u tests: %s" % (len(failed), failed))
@ -479,23 +533,48 @@ def run_tests(steps):
return passed
if __name__ == "__main__":
############## main program #############
''' main program '''
os.environ['PYTHONUNBUFFERED'] = '1'
os.putenv('TMPDIR', util.reltopdir('tmp'))
parser = optparse.OptionParser("autotest")
parser.add_option("--skip", type='string', default='', help='list of steps to skip (comma separated)')
parser.add_option("--list", action='store_true', default=False, help='list the available steps')
parser.add_option("--viewerip", default=None, help='IP address to send MAVLink and fg packets to')
parser.add_option("--map", action='store_true', default=False, help='show map')
parser.add_option("--experimental", default=False, action='store_true', help='enable experimental tests')
parser.add_option("--timeout", default=3000, type='int', help='maximum runtime in seconds')
parser.add_option("--frame", type='string', default=None, help='specify frame type')
parser.add_option("--skip",
type='string',
default='',
help='list of steps to skip (comma separated)')
parser.add_option("--list",
action='store_true',
default=False,
help='list the available steps')
parser.add_option("--viewerip",
default=None,
help='IP address to send MAVLink and fg packets to')
parser.add_option("--map",
action='store_true',
default=False,
help='show map')
parser.add_option("--experimental",
default=False,
action='store_true',
help='enable experimental tests')
parser.add_option("--timeout",
default=3000,
type='int',
help='maximum runtime in seconds')
parser.add_option("--frame",
type='string',
default=None,
help='specify frame type')
group_build = optparse.OptionGroup(parser, "Build options")
group_build.add_option("--no-configure", default=False, action='store_true', help='do not configure before building', dest="no_configure")
group_build.add_option("--no-configure",
default=False,
action='store_true',
help='do not configure before building',
dest="no_configure")
group_build.add_option("-j", default=None, type='int', help='build CPUs')
group_build.add_option("--no-clean",
default=False,
@ -529,38 +608,37 @@ if __name__ == "__main__":
opts, args = parser.parse_args()
steps = [
'prerequisites',
'build.All',
'build.Binaries',
# 'build.DevRelease',
'build.Examples',
'build.Parameters',
'prerequisites',
'build.All',
'build.Binaries',
# 'build.DevRelease',
'build.Examples',
'build.Parameters',
'build.ArduPlane',
'defaults.ArduPlane',
'fly.ArduPlane',
'fly.QuadPlane',
'build.ArduPlane',
'defaults.ArduPlane',
'fly.ArduPlane',
'fly.QuadPlane',
'build.APMrover2',
'defaults.APMrover2',
'drive.APMrover2',
'build.APMrover2',
'defaults.APMrover2',
'drive.APMrover2',
'build.ArduCopter',
'defaults.ArduCopter',
'fly.ArduCopter',
'build.ArduCopter',
'defaults.ArduCopter',
'fly.ArduCopter',
'build.Helicopter',
'fly.CopterAVC',
'build.Helicopter',
'fly.CopterAVC',
'build.AntennaTracker',
'build.AntennaTracker',
'build.ArduSub',
'defaults.ArduSub',
'dive.ArduSub',
'build.ArduSub',
'defaults.ArduSub',
'dive.ArduSub',
'convertgpx',
'convertgpx',
]
skipsteps = opts.skip.split(',')
@ -590,7 +668,8 @@ if __name__ == "__main__":
# allow a wildcard list of steps
matched = []
for a in args:
matches = [step for step in steps if fnmatch.fnmatch(step.lower(), a.lower())]
matches = [step for step in steps
if fnmatch.fnmatch(step.lower(), a.lower())]
if not len(matches):
print("No steps matched {}".format(a))
sys.exit(1)
@ -598,7 +677,7 @@ if __name__ == "__main__":
steps = matched
# skip steps according to --skip option:
steps_to_run = [ s for s in steps if should_run_step(s) ]
steps_to_run = [s for s in steps if should_run_step(s)]
results = TestResults()
@ -609,6 +688,6 @@ if __name__ == "__main__":
util.pexpect_close_all()
sys.exit(1)
except Exception:
# make sure we kill off any children
# make sure we kill off any children
util.pexpect_close_all()
raise