mirror of https://github.com/ArduPilot/ardupilot
autotest: correct run_one_test case (vehicle.testname case)
This commit is contained in:
parent
1fec88af21
commit
2e2e34d784
|
@ -360,6 +360,7 @@ suplementary_test_binary_map = {
|
||||||
"test.CAN": "sitl_periph_gps.AP_Periph",
|
"test.CAN": "sitl_periph_gps.AP_Periph",
|
||||||
}
|
}
|
||||||
|
|
||||||
|
from common import Test
|
||||||
def run_specific_test(step, *args, **kwargs):
|
def run_specific_test(step, *args, **kwargs):
|
||||||
t = split_specific_test_step(step)
|
t = split_specific_test_step(step)
|
||||||
if t is None:
|
if t is None:
|
||||||
|
@ -372,12 +373,10 @@ def run_specific_test(step, *args, **kwargs):
|
||||||
|
|
||||||
print("Got %s" % str(tester))
|
print("Got %s" % str(tester))
|
||||||
for a in tester.tests():
|
for a in tester.tests():
|
||||||
if hasattr(a, 'name'):
|
if not hasattr(a, 'name'):
|
||||||
name = a.name
|
a = Test(a[0], a[1], a[2])
|
||||||
else:
|
print("Got %s" % (a.name))
|
||||||
name = a[0]
|
if a.name == test:
|
||||||
print("Got %s" % (name))
|
|
||||||
if name == test:
|
|
||||||
return tester.run_tests([a])
|
return tester.run_tests([a])
|
||||||
print("Failed to find test %s on %s" % (test, testname))
|
print("Failed to find test %s on %s" % (test, testname))
|
||||||
sys.exit(1)
|
sys.exit(1)
|
||||||
|
|
Loading…
Reference in New Issue