Tools: split Copter tests into two runs to balance time on travis

This commit is contained in:
Andy Piper 2020-02-21 22:27:18 +00:00 committed by Andrew Tridgell
parent 41b41c05f3
commit 05a0fe615b
5 changed files with 37 additions and 14 deletions

View File

@ -60,7 +60,7 @@ matrix:
include:
- if: type != cron
compiler: "gcc"
env: CI_BUILD_TARGET="revo-bootloader periph-build CubeOrange-bootloader iofirmware stm32f7 stm32h7 fmuv2-plane"
env: CI_BUILD_TARGET="revo-bootloader periph-build CubeOrange-bootloader iofirmware stm32f7 stm32h7 fmuv2-plane sitltest-copter-extra"
- if: type != cron
compiler: "gcc"
env: CI_BUILD_TARGET="sitltest-copter"

View File

@ -4811,22 +4811,10 @@ class AutoTestCopter(AutoTest):
"Test onboard compass calibration",
self.test_onboard_compass_calibration),
("DynamicNotches",
"Fly Dynamic Notches",
self.fly_dynamic_notches),
("GyroFFT",
"Fly Gyro FFT",
self.fly_gyro_fft),
("RangeFinderDrivers",
"Test rangefinder drivers",
self.fly_rangefinder_drivers),
("MotorVibration",
"Fly motor vibration test",
self.fly_motor_vibration),
("ParameterValidation",
"Test parameters are checked for validity",
self.test_parameter_validation),
@ -5062,3 +5050,31 @@ class AutoTestHeli(AutoTestCopter):
upload_logs=len(self.fail_list) > 0))
])
return ret
class AutoTestCopterExtra(AutoTestCopter):
def log_name(self):
return "ArduCopter"
def tests(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

View File

@ -251,6 +251,7 @@ def should_run_step(step):
__bin_names = {
"ArduCopter": "arducopter",
"ArduCopterExtra": "arducopter",
"ArduPlane": "arduplane",
"APMrover2": "ardurover",
"AntennaTracker": "antennatracker",
@ -302,6 +303,7 @@ def find_specific_test_to_run(step):
tester_class_map = {
"fly.ArduCopter": arducopter.AutoTestCopter,
"fly.ArduCopterExtra": arducopter.AutoTestCopterExtra,
"fly.ArduPlane": arduplane.AutoTestPlane,
"fly.QuadPlane": quadplane.AutoTestQuadPlane,
"drive.APMrover2": apmrover2.AutoTestRover,
@ -769,6 +771,7 @@ if __name__ == "__main__":
'build.ArduCopter',
'defaults.ArduCopter',
'fly.ArduCopter',
'fly.ArduCopterExtra',
'build.Helicopter',
'fly.CopterAVC',

View File

@ -78,6 +78,10 @@ for t in $CI_BUILD_TARGET; do
run_autotest "Copter" "build.ArduCopter" "fly.ArduCopter"
continue
fi
if [ "$t" == "sitltest-copter-extra" ]; then
run_autotest "Copter" "build.ArduCopter" "fly.ArduCopterExtra"
continue
fi
if [ "$t" == "sitltest-plane" ]; then
run_autotest "Plane" "build.ArduPlane" "fly.ArduPlane"
continue

View File

@ -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
./Tools/autotest/autotest.py $OPTS build.ArduCopter fly.ArduCopter fly.ArduCopterExtra
./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