autotest: canonicalise step names (e.g. drive.APMrover2 -> test.Rover)

Map from older step names to newer test names added for
backwards-compatability
This commit is contained in:
Peter Barker 2020-03-26 07:47:28 +11:00 committed by Peter Barker
parent 051a7dc298
commit be49396d32

View File

@ -242,16 +242,15 @@ def should_run_step(step):
__bin_names = {
"ArduCopter": "arducopter",
"ArduCopterTests1": "arducopter",
"ArduCopterTests2": "arducopter",
"ArduPlane": "arduplane",
"APMrover2": "ardurover",
"AntennaTracker": "antennatracker",
"CopterAVC": "arducopter-heli",
"Copter": "arducopter",
"CopterTests1": "arducopter",
"CopterTests2": "arducopter",
"Plane": "arduplane",
"Rover": "ardurover",
"Tracker": "antennatracker",
"Helicopter": "arducopter-heli",
"QuadPlane": "arduplane",
"ArduSub": "ardusub",
"balancebot": "ardurover",
"Sub": "ardusub",
"BalanceBot": "ardurover",
}
@ -295,16 +294,16 @@ def find_specific_test_to_run(step):
return "%s.%s" % (testname, test)
tester_class_map = {
"fly.ArduCopter": arducopter.AutoTestCopter,
"fly.ArduCopterTests1": arducopter.AutoTestCopterTests1,
"fly.ArduCopterTests2": arducopter.AutoTestCopterTests2,
"fly.ArduPlane": arduplane.AutoTestPlane,
"fly.QuadPlane": quadplane.AutoTestQuadPlane,
"drive.APMrover2": apmrover2.AutoTestRover,
"drive.balancebot": balancebot.AutoTestBalanceBot,
"fly.CopterAVC": arducopter.AutoTestHeli,
"dive.ArduSub": ardusub.AutoTestSub,
"test.AntennaTracker": antennatracker.AutoTestTracker,
"test.Copter": arducopter.AutoTestCopter,
"test.CopterTests1": arducopter.AutoTestCopterTests1,
"test.CopterTests2": arducopter.AutoTestCopterTests2,
"test.Plane": arduplane.AutoTestPlane,
"test.QuadPlane": quadplane.AutoTestQuadPlane,
"test.Rover": apmrover2.AutoTestRover,
"test.BalanceBot": balancebot.AutoTestBalanceBot,
"test.Helicopter,": arducopter.AutoTestHeli,
"test.Sub": ardusub.AutoTestSub,
"test.Tracker": antennatracker.AutoTestTracker,
}
def run_specific_test(step, *args, **kwargs):
@ -342,22 +341,22 @@ def run_step(step):
}
vehicle_binary = None
if step == 'build.ArduPlane':
if step == 'build.Plane':
vehicle_binary = 'bin/arduplane'
if step == 'build.APMrover2':
if step == 'build.Rover':
vehicle_binary = 'bin/ardurover'
if step == 'build.ArduCopter':
if step == 'build.Copter':
vehicle_binary = 'bin/arducopter'
if step == 'build.AntennaTracker':
if step == 'build.Tracker':
vehicle_binary = 'bin/antennatracker'
if step == 'build.Helicopter':
vehicle_binary = 'bin/arducopter-heli'
if step == 'build.ArduSub':
if step == 'build.Sub':
vehicle_binary = 'bin/ardusub'
if vehicle_binary is not None:
@ -384,7 +383,7 @@ def run_step(step):
if opts.speedup is not None:
fly_opts["speedup"] = opts.speedup
# handle "fly.ArduCopter" etc:
# handle "test.Copter" etc:
if step in tester_class_map:
t = tester_class_map[step](binary, **fly_opts)
return (t.autotest(), t)
@ -752,40 +751,77 @@ if __name__ == "__main__":
'build.examples',
'run.examples',
'build.ArduPlane',
'defaults.ArduPlane',
'fly.ArduPlane',
'fly.QuadPlane',
'build.Plane',
'defaults.Plane',
'test.Plane',
'test.QuadPlane',
'build.APMrover2',
'defaults.APMrover2',
'drive.APMrover2',
'drive.balancebot',
'build.Rover',
'defaults.Rover',
'test.Rover',
'test.BalanceBot',
'build.ArduCopter',
'defaults.ArduCopter',
'fly.ArduCopter',
'build.Copter',
'defaults.Copter',
'test.Copter',
'build.Helicopter',
'fly.CopterAVC',
'test.Helicopter',
'build.AntennaTracker',
'defaults.AntennaTracker',
'test.AntennaTracker',
'build.Tracker',
'defaults.Tracker',
'test.Tracker',
'build.ArduSub',
'defaults.ArduSub',
'dive.ArduSub',
'build.Sub',
'defaults.Sub',
'test.Sub',
'convertgpx',
]
moresteps = [
'fly.ArduCopterTests1',
'fly.ArduCopterTests2',
'test.CopterTests1',
'test.CopterTests2',
]
# canonicalise the step names. This allows
# backwards-compatability from the hodge-podge
# fly.ArduCopter/drive.APMrover2 to the more common test.Copter
# test.Rover
step_mapping = {
"build.ArduPlane": "build.Plane",
"build.ArduCopter": "build.Copter",
"build.APMrover2": "build.Rover",
"build.ArduSub": "build.Sub",
"build.AntennaTracker": "build.Tracker",
"fly.ArduCopter": "test.Copter",
"fly.ArduPlane": "test.Plane",
"fly.QuadPlane": "test.QuadPlane",
"dive.ArduSub": "test.Sub",
"drive.APMrover2": "test.Rover",
"drive.BalanceBot": "test.BalanceBot",
"drive.balancebot": "test.BalanceBot",
"fly.CopterAVC": "test.Helicopter",
"test.AntennaTracker": "test.Tracker",
"defaults.ArduCopter": "defaults.Copter",
"defaults.ArduPlane": "defaults.Plane",
"defaults.ArduSub": "defaults.Sub",
"defaults.APMrover2": "defaults.Rover",
"defaults.AntennaTracker": "defaults.Tracker",
"fly.ArduCopterTests1": "test.CopterTests1",
"fly.ArduCopterTests2": "test.CopterTests2",
}
# form up a list of bits NOT to run, mapping from old step names
# to new step names as appropriate.
skipsteps = opts.skip.split(',')
new_skipsteps = []
for skipstep in skipsteps:
if skipstep in step_mapping:
new_skipsteps.append(step_mapping[skipstep])
else:
new_skipsteps.append(skipstep)
skipsteps = new_skipsteps
# ensure we catch timeouts
signal.signal(signal.SIGALRM, alarm_handler)
@ -808,6 +844,14 @@ if __name__ == "__main__":
atexit.register(util.pexpect_close_all)
# provide backwards-compatability from (e.g.) drive.APMrover2 -> test.Rover
newargs = []
for arg in args:
for _from, to in step_mapping.items():
arg = re.sub("^%s" % _from, to, arg)
newargs.append(arg)
args = newargs
if len(args) > 0:
# allow a wildcard list of steps
matched = []