autotest: restore fly.ArduCopter as running all tests
the test list for ArduCopter is made up of those from tests1 and tests2
This commit is contained in:
parent
9fb2914209
commit
82f53abee2
@ -4597,7 +4597,7 @@ class AutoTestCopter(AutoTest):
|
||||
self.drain_mav()
|
||||
self.assert_prearm_failure("Check MOT_PWM_MIN/MAX")
|
||||
|
||||
def tests(self):
|
||||
def tests1(self):
|
||||
'''return list of all tests'''
|
||||
ret = super(AutoTestCopter, self).tests()
|
||||
ret.extend([
|
||||
@ -4831,6 +4831,35 @@ class AutoTestCopter(AutoTest):
|
||||
])
|
||||
return ret
|
||||
|
||||
def tests2(self):
|
||||
'''return list of all tests'''
|
||||
ret = ([
|
||||
("MotorVibration",
|
||||
"Fly motor vibration test",
|
||||
self.fly_motor_vibration),
|
||||
|
||||
("DynamicNotches",
|
||||
"Fly Dynamic Notches",
|
||||
self.fly_dynamic_notches),
|
||||
|
||||
("GyroFFT",
|
||||
"Fly Gyro FFT",
|
||||
self.fly_gyro_fft),
|
||||
|
||||
("LogDownLoad",
|
||||
"Log download",
|
||||
lambda: self.log_download(
|
||||
self.buildlogs_path("ArduCopter-log.bin"),
|
||||
upload_logs=len(self.fail_list) > 0))
|
||||
])
|
||||
return ret
|
||||
|
||||
def tests(self):
|
||||
ret = []
|
||||
ret.extend(self.tests1())
|
||||
ret.extend(self.tests2())
|
||||
return ret
|
||||
|
||||
def disabled_tests(self):
|
||||
return {
|
||||
"Parachute": "See https://github.com/ArduPilot/ardupilot/issues/4702",
|
||||
@ -5051,30 +5080,14 @@ class AutoTestHeli(AutoTestCopter):
|
||||
])
|
||||
return ret
|
||||
|
||||
class AutoTestCopterExtra(AutoTestCopter):
|
||||
|
||||
def log_name(self):
|
||||
return "ArduCopter"
|
||||
class AutoTestCopterTests1(AutoTestCopter):
|
||||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
ret = ([
|
||||
("MotorVibration",
|
||||
"Fly motor vibration test",
|
||||
self.fly_motor_vibration),
|
||||
return self.tests1()
|
||||
|
||||
("DynamicNotches",
|
||||
"Fly Dynamic Notches",
|
||||
self.fly_dynamic_notches),
|
||||
|
||||
("GyroFFT",
|
||||
"Fly Gyro FFT",
|
||||
self.fly_gyro_fft),
|
||||
class AutoTestCopterTests2(AutoTestCopter):
|
||||
|
||||
("LogDownLoad",
|
||||
"Log download",
|
||||
lambda: self.log_download(
|
||||
self.buildlogs_path("ArduCopter-log.bin"),
|
||||
upload_logs=len(self.fail_list) > 0))
|
||||
])
|
||||
return ret
|
||||
def tests(self):
|
||||
return self.tests2()
|
||||
|
@ -251,7 +251,8 @@ def should_run_step(step):
|
||||
|
||||
__bin_names = {
|
||||
"ArduCopter": "arducopter",
|
||||
"ArduCopterExtra": "arducopter",
|
||||
"ArduCopterTests1": "arducopter",
|
||||
"ArduCopterTests2": "arducopter",
|
||||
"ArduPlane": "arduplane",
|
||||
"APMrover2": "ardurover",
|
||||
"AntennaTracker": "antennatracker",
|
||||
@ -303,7 +304,8 @@ def find_specific_test_to_run(step):
|
||||
|
||||
tester_class_map = {
|
||||
"fly.ArduCopter": arducopter.AutoTestCopter,
|
||||
"fly.ArduCopterExtra": arducopter.AutoTestCopterExtra,
|
||||
"fly.ArduCopterTests1": arducopter.AutoTestCopterTests1,
|
||||
"fly.ArduCopterTests2": arducopter.AutoTestCopterTests2,
|
||||
"fly.ArduPlane": arduplane.AutoTestPlane,
|
||||
"fly.QuadPlane": quadplane.AutoTestQuadPlane,
|
||||
"drive.APMrover2": apmrover2.AutoTestRover,
|
||||
@ -771,7 +773,6 @@ if __name__ == "__main__":
|
||||
'build.ArduCopter',
|
||||
'defaults.ArduCopter',
|
||||
'fly.ArduCopter',
|
||||
'fly.ArduCopterExtra',
|
||||
|
||||
'build.Helicopter',
|
||||
'fly.CopterAVC',
|
||||
@ -787,6 +788,11 @@ if __name__ == "__main__":
|
||||
'convertgpx',
|
||||
]
|
||||
|
||||
moresteps = [
|
||||
'fly.ArduCopterTests1',
|
||||
'fly.ArduCopterTests2',
|
||||
]
|
||||
|
||||
skipsteps = opts.skip.split(',')
|
||||
|
||||
# ensure we catch timeouts
|
||||
@ -820,6 +826,9 @@ if __name__ == "__main__":
|
||||
if x is not None:
|
||||
matches.append(x)
|
||||
|
||||
if a in moresteps:
|
||||
matches.append(a)
|
||||
|
||||
if not len(matches):
|
||||
print("No steps matched {}".format(a))
|
||||
sys.exit(1)
|
||||
|
@ -688,6 +688,9 @@ class AutoTest(ABC):
|
||||
use_map=False,
|
||||
_show_test_timings=False):
|
||||
|
||||
if binary is None:
|
||||
raise ValueError("Should always have a binary")
|
||||
|
||||
self.binary = binary
|
||||
self.valgrind = valgrind
|
||||
self.gdb = gdb
|
||||
|
@ -74,12 +74,12 @@ function run_autotest() {
|
||||
|
||||
for t in $CI_BUILD_TARGET; do
|
||||
# special case for SITL testing in CI
|
||||
if [ "$t" == "sitltest-copter" ]; then
|
||||
run_autotest "Copter" "build.ArduCopter" "fly.ArduCopter"
|
||||
if [ "$t" == "sitltest-copter-tests1" ]; then
|
||||
run_autotest "Copter" "build.ArduCopter" "fly.ArduCopter.Tests2"
|
||||
continue
|
||||
fi
|
||||
if [ "$t" == "sitltest-copter-extra" ]; then
|
||||
run_autotest "Copter" "build.ArduCopter" "fly.ArduCopterExtra"
|
||||
if [ "$t" == "sitltest-copter-tests2" ]; then
|
||||
run_autotest "Copter" "build.ArduCopter" "fly.ArduCopter.Tests1"
|
||||
continue
|
||||
fi
|
||||
if [ "$t" == "sitltest-plane" ]; then
|
||||
|
@ -31,7 +31,7 @@ rm -rf build
|
||||
# Run main vehicle tests
|
||||
./Tools/autotest/autotest.py $OPTS build.ArduPlane fly.ArduPlane fly.QuadPlane
|
||||
./Tools/autotest/autotest.py $OPTS build.ArduSub dive.ArduSub
|
||||
./Tools/autotest/autotest.py $OPTS build.ArduCopter fly.ArduCopter fly.ArduCopterExtra
|
||||
./Tools/autotest/autotest.py $OPTS build.ArduCopter fly.ArduCopter fly.ArduCopter
|
||||
./Tools/autotest/autotest.py $OPTS build.Helicopter fly.CopterAVC
|
||||
./Tools/autotest/autotest.py $OPTS build.AntennaTracker test.AntennaTracker
|
||||
./Tools/autotest/autotest.py $OPTS build.APMrover2 drive.APMrover2
|
||||
|
Loading…
Reference in New Issue
Block a user