mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AutoTest: break copter autotests into smaller "under 10 minute" chunks to speedup github actions CI
This commit is contained in:
parent
e4056086e0
commit
586e9f80d5
9
.github/workflows/test_sitl_copter.yml
vendored
9
.github/workflows/test_sitl_copter.yml
vendored
@ -92,8 +92,13 @@ jobs:
|
|||||||
fail-fast: false # don't cancel if a job from the matrix fails
|
fail-fast: false # don't cancel if a job from the matrix fails
|
||||||
matrix:
|
matrix:
|
||||||
config: [
|
config: [
|
||||||
sitltest-copter-tests1,
|
sitltest-copter-tests1a,
|
||||||
sitltest-copter-tests2
|
sitltest-copter-tests1b,
|
||||||
|
sitltest-copter-tests1c,
|
||||||
|
sitltest-copter-tests1d,
|
||||||
|
sitltest-copter-tests1e,
|
||||||
|
sitltest-copter-tests2a,
|
||||||
|
sitltest-copter-tests2b,
|
||||||
]
|
]
|
||||||
|
|
||||||
steps:
|
steps:
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
|
|
||||||
[![Gitter](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/ArduPilot/ardupilot?utm_source=badge&utm_medium=badge&utm_campaign=pr-badge&utm_content=badge)
|
[![Gitter](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/ArduPilot/ardupilot?utm_source=badge&utm_medium=badge&utm_campaign=pr-badge&utm_content=badge)
|
||||||
|
|
||||||
[![Build Travis](https://travis-ci.org/ArduPilot/ardupilot.svg?branch=master)](https://travis-ci.org/ArduPilot/ardupilot) [![Build SemaphoreCI](https://semaphoreci.com/api/v1/ardupilot/ardupilot/branches/master/badge.svg)](https://semaphoreci.com/ardupilot/ardupilot) [![Build Status](https://dev.azure.com/ardupilot-org/ardupilot/_apis/build/status/ArduPilot.ardupilot?branchName=master)](https://dev.azure.com/ardupilot-org/ardupilot/_build/latest?definitionId=1&branchName=master)
|
[![Build Travis](https://travis-ci.com/ArduPilot/ardupilot.svg?branch=master)](https://travis-ci.com/ArduPilot/ardupilot) [![Build SemaphoreCI](https://semaphoreci.com/api/v1/ardupilot/ardupilot/branches/master/badge.svg)](https://semaphoreci.com/ardupilot/ardupilot) [![Build Status](https://dev.azure.com/ardupilot-org/ardupilot/_apis/build/status/ArduPilot.ardupilot?branchName=master)](https://dev.azure.com/ardupilot-org/ardupilot/_build/latest?definitionId=1&branchName=master)
|
||||||
|
|
||||||
[![Coverity Scan Build Status](https://scan.coverity.com/projects/5331/badge.svg)](https://scan.coverity.com/projects/ardupilot-ardupilot)
|
[![Coverity Scan Build Status](https://scan.coverity.com/projects/5331/badge.svg)](https://scan.coverity.com/projects/ardupilot-ardupilot)
|
||||||
|
|
||||||
|
@ -5289,22 +5289,31 @@ class AutoTestCopter(AutoTest):
|
|||||||
if ex is not None:
|
if ex is not None:
|
||||||
raise ex
|
raise ex
|
||||||
|
|
||||||
|
# a wrapper around all the 1A,1B,1C..etc tests for travis
|
||||||
def tests1(self):
|
def tests1(self):
|
||||||
'''return list of all tests'''
|
ret = ([])
|
||||||
ret = super(AutoTestCopter, self).tests()
|
ret.extend(self.tests1a())
|
||||||
ret.extend([
|
ret.extend(self.tests1b())
|
||||||
|
ret.extend(self.tests1c())
|
||||||
|
ret.extend(self.tests1d())
|
||||||
|
ret.extend(self.tests1e())
|
||||||
|
return ret
|
||||||
|
|
||||||
|
def tests1a(self):
|
||||||
|
'''return list of all tests'''
|
||||||
|
ret = super(AutoTestCopter, self).tests() #about 5 mins and ~20 initial tests from autotest/common.py
|
||||||
|
ret.extend([
|
||||||
("NavDelayTakeoffAbsTime",
|
("NavDelayTakeoffAbsTime",
|
||||||
"Fly Nav Delay (takeoff)",
|
"Fly Nav Delay (takeoff)",
|
||||||
self.fly_nav_takeoff_delay_abstime),
|
self.fly_nav_takeoff_delay_abstime), #19s
|
||||||
|
|
||||||
("NavDelayAbsTime",
|
("NavDelayAbsTime",
|
||||||
"Fly Nav Delay (AbsTime)",
|
"Fly Nav Delay (AbsTime)",
|
||||||
self.fly_nav_delay_abstime),
|
self.fly_nav_delay_abstime), #20s
|
||||||
|
|
||||||
("NavDelay",
|
("NavDelay",
|
||||||
"Fly Nav Delay",
|
"Fly Nav Delay",
|
||||||
self.fly_nav_delay),
|
self.fly_nav_delay), #19s
|
||||||
|
|
||||||
("GuidedSubModeChange",
|
("GuidedSubModeChange",
|
||||||
"Test submode change",
|
"Test submode change",
|
||||||
@ -5312,19 +5321,19 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
("LoiterToAlt",
|
("LoiterToAlt",
|
||||||
"Loiter-To-Alt",
|
"Loiter-To-Alt",
|
||||||
self.fly_loiter_to_alt),
|
self.fly_loiter_to_alt), #25s
|
||||||
|
|
||||||
("PayLoadPlaceMission",
|
("PayLoadPlaceMission",
|
||||||
"Payload Place Mission",
|
"Payload Place Mission",
|
||||||
self.fly_payload_place_mission),
|
self.fly_payload_place_mission), #44s
|
||||||
|
|
||||||
("PrecisionLoiterCompanion",
|
("PrecisionLoiterCompanion",
|
||||||
"Precision Loiter (Companion)",
|
"Precision Loiter (Companion)",
|
||||||
self.fly_precision_companion),
|
self.fly_precision_companion), #29s
|
||||||
|
|
||||||
("PrecisionLandingSITL",
|
("PrecisionLandingSITL",
|
||||||
"Precision Landing (SITL)",
|
"Precision Landing (SITL)",
|
||||||
self.fly_precision_sitl),
|
self.fly_precision_sitl), #29s
|
||||||
|
|
||||||
("SetModesViaModeSwitch",
|
("SetModesViaModeSwitch",
|
||||||
"Set modes via modeswitch",
|
"Set modes via modeswitch",
|
||||||
@ -5338,47 +5347,67 @@ class AutoTestCopter(AutoTest):
|
|||||||
"Test random aux mode options",
|
"Test random aux mode options",
|
||||||
self.test_aux_switch_options),
|
self.test_aux_switch_options),
|
||||||
|
|
||||||
("AutoTune", "Fly AUTOTUNE mode", self.fly_autotune),
|
("AutoTune",
|
||||||
|
"Fly AUTOTUNE mode",
|
||||||
|
self.fly_autotune), #73s
|
||||||
|
])
|
||||||
|
return ret
|
||||||
|
|
||||||
|
def tests1b(self):
|
||||||
|
'''return list of all tests'''
|
||||||
|
ret = ([
|
||||||
("ThrowMode", "Fly Throw Mode", self.fly_throw_mode),
|
("ThrowMode", "Fly Throw Mode", self.fly_throw_mode),
|
||||||
|
|
||||||
("BrakeMode", "Fly Brake Mode", self.fly_brake_mode),
|
("BrakeMode", "Fly Brake Mode", self.fly_brake_mode),
|
||||||
|
|
||||||
("RecordThenPlayMission",
|
("RecordThenPlayMission",
|
||||||
"Use switches to toggle in mission, then fly it",
|
"Use switches to toggle in mission, then fly it",
|
||||||
self.fly_square),
|
self.fly_square), #27s
|
||||||
|
|
||||||
("ThrottleFailsafe",
|
("ThrottleFailsafe",
|
||||||
"Test Throttle Failsafe",
|
"Test Throttle Failsafe",
|
||||||
self.fly_throttle_failsafe),
|
self.fly_throttle_failsafe), #173s
|
||||||
|
|
||||||
("GCSFailsafe",
|
("GCSFailsafe",
|
||||||
"Test GCS Failsafe",
|
"Test GCS Failsafe",
|
||||||
self.fly_gcs_failsafe),
|
self.fly_gcs_failsafe), #239s
|
||||||
|
|
||||||
|
#this group has the smallest runtime right now at around 5mins,
|
||||||
|
# so add more tests here, till its around 9-10mins, then make a new group
|
||||||
|
])
|
||||||
|
return ret
|
||||||
|
|
||||||
|
def tests1c(self):
|
||||||
|
'''return list of all tests'''
|
||||||
|
ret = ([
|
||||||
("BatteryFailsafe",
|
("BatteryFailsafe",
|
||||||
"Fly Battery Failsafe",
|
"Fly Battery Failsafe",
|
||||||
self.fly_battery_failsafe),
|
self.fly_battery_failsafe), #164s
|
||||||
|
|
||||||
("StabilityPatch",
|
("StabilityPatch",
|
||||||
"Fly stability patch",
|
"Fly stability patch",
|
||||||
lambda: self.fly_stability_patch(30)),
|
lambda: self.fly_stability_patch(30)), #17s
|
||||||
|
|
||||||
("AC_Avoidance_Proximity",
|
("AC_Avoidance_Proximity",
|
||||||
"Test proximity avoidance slide behaviour",
|
"Test proximity avoidance slide behaviour",
|
||||||
self.fly_proximity_avoidance_test),
|
self.fly_proximity_avoidance_test), #41s
|
||||||
|
|
||||||
("AC_Avoidance_Fence",
|
("AC_Avoidance_Fence",
|
||||||
"Test fence avoidance slide behaviour",
|
"Test fence avoidance slide behaviour",
|
||||||
self.fly_fence_avoidance_test),
|
self.fly_fence_avoidance_test),
|
||||||
|
|
||||||
("AC_Avoidance_Beacon",
|
("AC_Avoidance_Beacon",
|
||||||
"Test beacon avoidance slide behaviour",
|
"Test beacon avoidance slide behaviour",
|
||||||
self.fly_beacon_avoidance_test),
|
self.fly_beacon_avoidance_test),#28s
|
||||||
|
])
|
||||||
|
return ret
|
||||||
|
|
||||||
|
def tests1d(self):
|
||||||
|
'''return list of all tests'''
|
||||||
|
ret = ([
|
||||||
("HorizontalFence",
|
("HorizontalFence",
|
||||||
"Test horizontal fence",
|
"Test horizontal fence",
|
||||||
self.fly_fence_test),
|
self.fly_fence_test), #20s
|
||||||
|
|
||||||
("HorizontalAvoidFence",
|
("HorizontalAvoidFence",
|
||||||
"Test horizontal Avoidance fence",
|
"Test horizontal Avoidance fence",
|
||||||
@ -5386,13 +5415,15 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
("MaxAltFence",
|
("MaxAltFence",
|
||||||
"Test Max Alt Fence",
|
"Test Max Alt Fence",
|
||||||
self.fly_alt_max_fence_test),
|
self.fly_alt_max_fence_test), #26s
|
||||||
|
|
||||||
("AutoTuneSwitch", "Fly AUTOTUNE on a switch", self.fly_autotune_switch),
|
("AutoTuneSwitch",
|
||||||
|
"Fly AUTOTUNE on a switch",
|
||||||
|
self.fly_autotune_switch), #105s
|
||||||
|
|
||||||
("GPSGlitchLoiter",
|
("GPSGlitchLoiter",
|
||||||
"GPS Glitch Loiter Test",
|
"GPS Glitch Loiter Test",
|
||||||
self.fly_gps_glitch_loiter_test),
|
self.fly_gps_glitch_loiter_test), #30s
|
||||||
|
|
||||||
("GPSGlitchAuto",
|
("GPSGlitchAuto",
|
||||||
"GPS Glitch Auto Test",
|
"GPS Glitch Auto Test",
|
||||||
@ -5412,11 +5443,11 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
("SuperSimpleCircle",
|
("SuperSimpleCircle",
|
||||||
"Fly a circle in SUPER SIMPLE mode",
|
"Fly a circle in SUPER SIMPLE mode",
|
||||||
self.fly_super_simple),
|
self.fly_super_simple), #38s
|
||||||
|
|
||||||
("ModeCircle",
|
("ModeCircle",
|
||||||
"Fly CIRCLE mode",
|
"Fly CIRCLE mode",
|
||||||
self.fly_circle),
|
self.fly_circle), #27s
|
||||||
|
|
||||||
("MagFail",
|
("MagFail",
|
||||||
"Test magnetometer failure",
|
"Test magnetometer failure",
|
||||||
@ -5424,7 +5455,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
("OpticalFlowLimits",
|
("OpticalFlowLimits",
|
||||||
"Fly Optical Flow limits",
|
"Fly Optical Flow limits",
|
||||||
self.fly_optical_flow_limits),
|
self.fly_optical_flow_limits), #27s
|
||||||
|
|
||||||
("MotorFail",
|
("MotorFail",
|
||||||
"Fly motor failure test",
|
"Fly motor failure test",
|
||||||
@ -5436,7 +5467,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
("CopterMission",
|
("CopterMission",
|
||||||
"Fly copter mission",
|
"Fly copter mission",
|
||||||
self.fly_auto_test),
|
self.fly_auto_test), #37s
|
||||||
|
|
||||||
("SplineLastWaypoint",
|
("SplineLastWaypoint",
|
||||||
"Test Spline as last waypoint",
|
"Test Spline as last waypoint",
|
||||||
@ -5444,7 +5475,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
("Gripper",
|
("Gripper",
|
||||||
"Test gripper",
|
"Test gripper",
|
||||||
self.test_gripper),
|
self.test_gripper), #28s
|
||||||
|
|
||||||
("TestGripperMission",
|
("TestGripperMission",
|
||||||
"Test Gripper mission items",
|
"Test Gripper mission items",
|
||||||
@ -5452,11 +5483,16 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
("VisionPosition",
|
("VisionPosition",
|
||||||
"Fly Vision Position",
|
"Fly Vision Position",
|
||||||
self.fly_vision_position),
|
self.fly_vision_position), #24s
|
||||||
|
])
|
||||||
|
return ret
|
||||||
|
|
||||||
|
def tests1e(self):
|
||||||
|
'''return list of all tests'''
|
||||||
|
ret = ([
|
||||||
("BeaconPosition",
|
("BeaconPosition",
|
||||||
"Fly Beacon Position",
|
"Fly Beacon Position",
|
||||||
self.fly_beacon_position),
|
self.fly_beacon_position), #56s
|
||||||
|
|
||||||
("RTLSpeed",
|
("RTLSpeed",
|
||||||
"Fly RTL Speed",
|
"Fly RTL Speed",
|
||||||
@ -5464,7 +5500,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
("Mount",
|
("Mount",
|
||||||
"Test Camera/Antenna Mount",
|
"Test Camera/Antenna Mount",
|
||||||
self.test_mount),
|
self.test_mount), #74s
|
||||||
|
|
||||||
("Button",
|
("Button",
|
||||||
"Test Buttons",
|
"Test Buttons",
|
||||||
@ -5476,11 +5512,11 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
("RangeFinder",
|
("RangeFinder",
|
||||||
"Test RangeFinder Basic Functionality",
|
"Test RangeFinder Basic Functionality",
|
||||||
self.test_rangefinder),
|
self.test_rangefinder), #23s
|
||||||
|
|
||||||
("SurfaceTracking",
|
("SurfaceTracking",
|
||||||
"Test Surface Tracking",
|
"Test Surface Tracking",
|
||||||
self.test_surface_tracking),
|
self.test_surface_tracking), #45s
|
||||||
|
|
||||||
("Parachute",
|
("Parachute",
|
||||||
"Test Parachute Functionality",
|
"Test Parachute Functionality",
|
||||||
@ -5498,8 +5534,9 @@ class AutoTestCopter(AutoTest):
|
|||||||
"Test mavlink MANUAL_CONTROL",
|
"Test mavlink MANUAL_CONTROL",
|
||||||
self.test_manual_control),
|
self.test_manual_control),
|
||||||
|
|
||||||
# Zigzag mode test
|
("ZigZag",
|
||||||
("ZigZag", "Fly ZigZag Mode", self.fly_zigzag_mode),
|
"Fly ZigZag Mode",
|
||||||
|
self.fly_zigzag_mode), #58s
|
||||||
|
|
||||||
("PosHoldTakeOff",
|
("PosHoldTakeOff",
|
||||||
"Fly POSHOLD takeoff",
|
"Fly POSHOLD takeoff",
|
||||||
@ -5507,11 +5544,11 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
("FOLLOW",
|
("FOLLOW",
|
||||||
"Fly follow mode",
|
"Fly follow mode",
|
||||||
self.fly_follow_mode),
|
self.fly_follow_mode), #80s
|
||||||
|
|
||||||
("RangeFinderDrivers",
|
("RangeFinderDrivers",
|
||||||
"Test rangefinder drivers",
|
"Test rangefinder drivers",
|
||||||
self.fly_rangefinder_drivers),
|
self.fly_rangefinder_drivers), #62s
|
||||||
|
|
||||||
("ParameterValidation",
|
("ParameterValidation",
|
||||||
"Test parameters are checked for validity",
|
"Test parameters are checked for validity",
|
||||||
@ -5531,48 +5568,62 @@ class AutoTestCopter(AutoTest):
|
|||||||
])
|
])
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
|
# a wrapper around all the 2A,2B,2C..etc tests for travis
|
||||||
def tests2(self):
|
def tests2(self):
|
||||||
|
ret = ([])
|
||||||
|
ret.extend(self.tests2a())
|
||||||
|
ret.extend(self.tests2b())
|
||||||
|
return ret
|
||||||
|
|
||||||
|
def tests2a(self):
|
||||||
|
'''return list of all tests'''
|
||||||
|
ret = ([
|
||||||
|
("FixedYawCalibration",
|
||||||
|
"Test Fixed Yaw Calibration", #about 20 secs
|
||||||
|
self.test_fixed_yaw_calibration), # something about SITLCompassCalibration appears to fail this one, so we put it first
|
||||||
|
|
||||||
|
# we run this single 8min-and-40s test on its own, apart from
|
||||||
|
# requiring FixedYawCalibration right before it because without it, it fails to calibrate
|
||||||
|
("SITLCompassCalibration", # this autotest appears to interfere with FixedYawCalibration, no idea why.
|
||||||
|
"Test SITL onboard compass calibration",
|
||||||
|
self.test_mag_calibration),
|
||||||
|
])
|
||||||
|
return ret
|
||||||
|
|
||||||
|
def tests2b(self): #this block currently around 9.5mins here
|
||||||
'''return list of all tests'''
|
'''return list of all tests'''
|
||||||
ret = ([
|
ret = ([
|
||||||
("MotorVibration",
|
("MotorVibration",
|
||||||
"Fly motor vibration test",
|
"Fly motor vibration test",
|
||||||
self.fly_motor_vibration),
|
self.fly_motor_vibration),
|
||||||
|
|
||||||
("DynamicNotches",
|
("DynamicNotches",
|
||||||
"Fly Dynamic Notches",
|
"Fly Dynamic Notches",
|
||||||
self.fly_dynamic_notches),
|
self.fly_dynamic_notches),
|
||||||
|
|
||||||
("GyroFFT",
|
("GyroFFT",
|
||||||
"Fly Gyro FFT",
|
"Fly Gyro FFT",
|
||||||
self.fly_gyro_fft),
|
self.fly_gyro_fft),
|
||||||
|
|
||||||
("FixedYawCalibration",
|
|
||||||
"Test Fixed Yaw Calibration",
|
|
||||||
self.test_fixed_yaw_calibration),
|
|
||||||
|
|
||||||
("GyroFFTHarmonic",
|
("GyroFFTHarmonic",
|
||||||
"Fly Gyro FFT Harmonic Matching",
|
"Fly Gyro FFT Harmonic Matching",
|
||||||
self.fly_gyro_fft_harmonic),
|
self.fly_gyro_fft_harmonic),
|
||||||
|
|
||||||
("SITLCompassCalibration",
|
|
||||||
"Test SITL onboard compass calibration",
|
|
||||||
self.test_mag_calibration),
|
|
||||||
|
|
||||||
("CompassReordering",
|
("CompassReordering",
|
||||||
"Test Compass reordering when priorities are changed",
|
"Test Compass reordering when priorities are changed",
|
||||||
self.test_mag_reordering),
|
self.test_mag_reordering), # 40sec?
|
||||||
|
|
||||||
("CRSF",
|
("CRSF",
|
||||||
"Test RC CRSF",
|
"Test RC CRSF",
|
||||||
self.test_crsf),
|
self.test_crsf), #20secs ish
|
||||||
|
|
||||||
("MotorTest",
|
("MotorTest",
|
||||||
"Run Motor Tests",
|
"Run Motor Tests",
|
||||||
self.test_motortest),
|
self.test_motortest), #20secs ish
|
||||||
|
|
||||||
("AltEstimation",
|
("AltEstimation",
|
||||||
"Test that Alt Estimation is mandatory for ALT_HOLD",
|
"Test that Alt Estimation is mandatory for ALT_HOLD",
|
||||||
self.test_alt_estimate_prearm),
|
self.test_alt_estimate_prearm), #20secs ish
|
||||||
|
|
||||||
("DataFlash",
|
("DataFlash",
|
||||||
"Test DataFlash Block backend",
|
"Test DataFlash Block backend",
|
||||||
@ -5904,12 +5955,33 @@ class AutoTestHeli(AutoTestCopter):
|
|||||||
}
|
}
|
||||||
|
|
||||||
class AutoTestCopterTests1(AutoTestCopter):
|
class AutoTestCopterTests1(AutoTestCopter):
|
||||||
|
|
||||||
def tests(self):
|
def tests(self):
|
||||||
return self.tests1()
|
return self.tests1()
|
||||||
|
class AutoTestCopterTests1a(AutoTestCopter):
|
||||||
|
def tests(self):
|
||||||
|
return self.tests1a()
|
||||||
|
class AutoTestCopterTests1b(AutoTestCopter):
|
||||||
|
def tests(self):
|
||||||
|
return self.tests1b()
|
||||||
|
class AutoTestCopterTests1c(AutoTestCopter):
|
||||||
|
def tests(self):
|
||||||
|
return self.tests1c()
|
||||||
|
class AutoTestCopterTests1d(AutoTestCopter):
|
||||||
|
def tests(self):
|
||||||
|
return self.tests1d()
|
||||||
|
class AutoTestCopterTests1e(AutoTestCopter):
|
||||||
|
def tests(self):
|
||||||
|
return self.tests1e()
|
||||||
|
|
||||||
class AutoTestCopterTests2(AutoTestCopter):
|
class AutoTestCopterTests2(AutoTestCopter):
|
||||||
|
|
||||||
def tests(self):
|
def tests(self):
|
||||||
return self.tests2()
|
return self.tests2()
|
||||||
|
class AutoTestCopterTests2a(AutoTestCopter):
|
||||||
|
def tests(self):
|
||||||
|
return self.tests2a()
|
||||||
|
class AutoTestCopterTests2b(AutoTestCopter):
|
||||||
|
def tests(self):
|
||||||
|
return self.tests2b()
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -262,7 +262,16 @@ def should_run_step(step):
|
|||||||
__bin_names = {
|
__bin_names = {
|
||||||
"Copter": "arducopter",
|
"Copter": "arducopter",
|
||||||
"CopterTests1": "arducopter",
|
"CopterTests1": "arducopter",
|
||||||
|
"CopterTests1a": "arducopter",
|
||||||
|
"CopterTests1b": "arducopter",
|
||||||
|
"CopterTests1c": "arducopter",
|
||||||
|
"CopterTests1d": "arducopter",
|
||||||
|
"CopterTests1e": "arducopter",
|
||||||
|
|
||||||
"CopterTests2": "arducopter",
|
"CopterTests2": "arducopter",
|
||||||
|
"CopterTests2a": "arducopter",
|
||||||
|
"CopterTests2b": "arducopter",
|
||||||
|
|
||||||
"Plane": "arduplane",
|
"Plane": "arduplane",
|
||||||
"Rover": "ardurover",
|
"Rover": "ardurover",
|
||||||
"Tracker": "antennatracker",
|
"Tracker": "antennatracker",
|
||||||
@ -313,8 +322,15 @@ def find_specific_test_to_run(step):
|
|||||||
|
|
||||||
tester_class_map = {
|
tester_class_map = {
|
||||||
"test.Copter": arducopter.AutoTestCopter,
|
"test.Copter": arducopter.AutoTestCopter,
|
||||||
"test.CopterTests1": arducopter.AutoTestCopterTests1,
|
"test.CopterTests1": arducopter.AutoTestCopterTests1, #travis-ci
|
||||||
"test.CopterTests2": arducopter.AutoTestCopterTests2,
|
"test.CopterTests1a": arducopter.AutoTestCopterTests1a, # 8m43s
|
||||||
|
"test.CopterTests1b": arducopter.AutoTestCopterTests1b, # 8m5s
|
||||||
|
"test.CopterTests1c": arducopter.AutoTestCopterTests1c, # 5m17s
|
||||||
|
"test.CopterTests1d": arducopter.AutoTestCopterTests1d, # 8m20s
|
||||||
|
"test.CopterTests1e": arducopter.AutoTestCopterTests1e, # 8m32s
|
||||||
|
"test.CopterTests2": arducopter.AutoTestCopterTests2, #travis-ci
|
||||||
|
"test.CopterTests2a": arducopter.AutoTestCopterTests2a, # 8m23s
|
||||||
|
"test.CopterTests2b": arducopter.AutoTestCopterTests2b, # 8m18s
|
||||||
"test.Plane": arduplane.AutoTestPlane,
|
"test.Plane": arduplane.AutoTestPlane,
|
||||||
"test.QuadPlane": quadplane.AutoTestQuadPlane,
|
"test.QuadPlane": quadplane.AutoTestQuadPlane,
|
||||||
"test.Rover": rover.AutoTestRover,
|
"test.Rover": rover.AutoTestRover,
|
||||||
@ -850,7 +866,16 @@ if __name__ == "__main__":
|
|||||||
|
|
||||||
moresteps = [
|
moresteps = [
|
||||||
'test.CopterTests1',
|
'test.CopterTests1',
|
||||||
|
'test.CopterTests1a',
|
||||||
|
'test.CopterTests1b',
|
||||||
|
'test.CopterTests1c',
|
||||||
|
'test.CopterTests1d',
|
||||||
|
'test.CopterTests1e',
|
||||||
|
|
||||||
'test.CopterTests2',
|
'test.CopterTests2',
|
||||||
|
'test.CopterTests2a',
|
||||||
|
'test.CopterTests2b',
|
||||||
|
|
||||||
'clang-scan-build',
|
'clang-scan-build',
|
||||||
]
|
]
|
||||||
|
|
||||||
@ -879,7 +904,16 @@ if __name__ == "__main__":
|
|||||||
"defaults.APMrover2": "defaults.Rover",
|
"defaults.APMrover2": "defaults.Rover",
|
||||||
"defaults.AntennaTracker": "defaults.Tracker",
|
"defaults.AntennaTracker": "defaults.Tracker",
|
||||||
"fly.ArduCopterTests1": "test.CopterTests1",
|
"fly.ArduCopterTests1": "test.CopterTests1",
|
||||||
|
"fly.ArduCopterTests1a": "test.CopterTests1a",
|
||||||
|
"fly.ArduCopterTests1b": "test.CopterTests1b",
|
||||||
|
"fly.ArduCopterTests1c": "test.CopterTests1c",
|
||||||
|
"fly.ArduCopterTests1d": "test.CopterTests1d",
|
||||||
|
"fly.ArduCopterTests1e": "test.CopterTests1e",
|
||||||
|
|
||||||
"fly.ArduCopterTests2": "test.CopterTests2",
|
"fly.ArduCopterTests2": "test.CopterTests2",
|
||||||
|
"fly.ArduCopterTests2a": "test.CopterTests2a",
|
||||||
|
"fly.ArduCopterTests2b": "test.CopterTests2b",
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
# form up a list of bits NOT to run, mapping from old step names
|
# form up a list of bits NOT to run, mapping from old step names
|
||||||
|
@ -1581,9 +1581,9 @@ class AutoTest(ABC):
|
|||||||
self.log_name()))
|
self.log_name()))
|
||||||
|
|
||||||
def start_test(self, description):
|
def start_test(self, description):
|
||||||
self.progress("#")
|
self.progress("##################################################################################")
|
||||||
self.progress("########## %s ##########" % description)
|
self.progress("########## %s ##########" % description)
|
||||||
self.progress("#")
|
self.progress("##################################################################################")
|
||||||
|
|
||||||
def try_symlink_tlog(self):
|
def try_symlink_tlog(self):
|
||||||
self.buildlog = self.buildlogs_path(self.log_name() + "-test.tlog")
|
self.buildlog = self.buildlogs_path(self.log_name() + "-test.tlog")
|
||||||
@ -4130,10 +4130,13 @@ Also, ignores heartbeats not from our target system'''
|
|||||||
for desc in self.test_timings.keys():
|
for desc in self.test_timings.keys():
|
||||||
if len(desc) > longest:
|
if len(desc) > longest:
|
||||||
longest = len(desc)
|
longest = len(desc)
|
||||||
|
tests_total_time = 0
|
||||||
for desc, test_time in sorted(self.test_timings.items(),
|
for desc, test_time in sorted(self.test_timings.items(),
|
||||||
key=self.show_test_timings_key_sorter):
|
key=self.show_test_timings_key_sorter):
|
||||||
fmt = "%" + str(longest) + "s: %.2fs"
|
fmt = "%" + str(longest) + "s: %.2fs"
|
||||||
|
tests_total_time += test_time;
|
||||||
self.progress(fmt % (desc, test_time))
|
self.progress(fmt % (desc, test_time))
|
||||||
|
self.progress(fmt % ("**--tests_total_time--**", tests_total_time))
|
||||||
|
|
||||||
def send_statustext(self, text):
|
def send_statustext(self, text):
|
||||||
if sys.version_info.major >= 3 and not isinstance(text, bytes):
|
if sys.version_info.major >= 3 and not isinstance(text, bytes):
|
||||||
|
@ -37,6 +37,9 @@ function run_autotest() {
|
|||||||
BVEHICLE="$2"
|
BVEHICLE="$2"
|
||||||
RVEHICLE="$3"
|
RVEHICLE="$3"
|
||||||
|
|
||||||
|
# report on what cpu's we have for later log review if needed
|
||||||
|
cat /proc/cpuinfo
|
||||||
|
|
||||||
if [ $mavproxy_installed -eq 0 ]; then
|
if [ $mavproxy_installed -eq 0 ]; then
|
||||||
echo "Installing MAVProxy"
|
echo "Installing MAVProxy"
|
||||||
pushd /tmp
|
pushd /tmp
|
||||||
@ -78,14 +81,48 @@ for t in $CI_BUILD_TARGET; do
|
|||||||
run_autotest "Heli" "build.Helicopter" "test.Helicopter"
|
run_autotest "Heli" "build.Helicopter" "test.Helicopter"
|
||||||
continue
|
continue
|
||||||
fi
|
fi
|
||||||
|
# travis-ci
|
||||||
if [ "$t" == "sitltest-copter-tests1" ]; then
|
if [ "$t" == "sitltest-copter-tests1" ]; then
|
||||||
run_autotest "Copter" "build.Copter" "test.CopterTests1"
|
run_autotest "Copter" "build.Copter" "test.CopterTests1"
|
||||||
continue
|
continue
|
||||||
fi
|
fi
|
||||||
|
#github actions ci
|
||||||
|
if [ "$t" == "sitltest-copter-tests1a" ]; then
|
||||||
|
run_autotest "Copter" "build.Copter" "test.CopterTests1a"
|
||||||
|
continue
|
||||||
|
fi
|
||||||
|
if [ "$t" == "sitltest-copter-tests1b" ]; then
|
||||||
|
run_autotest "Copter" "build.Copter" "test.CopterTests1b"
|
||||||
|
continue
|
||||||
|
fi
|
||||||
|
if [ "$t" == "sitltest-copter-tests1c" ]; then
|
||||||
|
run_autotest "Copter" "build.Copter" "test.CopterTests1c"
|
||||||
|
continue
|
||||||
|
fi
|
||||||
|
if [ "$t" == "sitltest-copter-tests1d" ]; then
|
||||||
|
run_autotest "Copter" "build.Copter" "test.CopterTests1d"
|
||||||
|
continue
|
||||||
|
fi
|
||||||
|
if [ "$t" == "sitltest-copter-tests1e" ]; then
|
||||||
|
run_autotest "Copter" "build.Copter" "test.CopterTests1e"
|
||||||
|
continue
|
||||||
|
fi
|
||||||
|
|
||||||
|
# travis-ci
|
||||||
if [ "$t" == "sitltest-copter-tests2" ]; then
|
if [ "$t" == "sitltest-copter-tests2" ]; then
|
||||||
run_autotest "Copter" "build.Copter" "test.CopterTests2"
|
run_autotest "Copter" "build.Copter" "test.CopterTests2"
|
||||||
continue
|
continue
|
||||||
fi
|
fi
|
||||||
|
#github actions ci
|
||||||
|
if [ "$t" == "sitltest-copter-tests2a" ]; then
|
||||||
|
run_autotest "Copter" "build.Copter" "test.CopterTests2a"
|
||||||
|
continue
|
||||||
|
fi
|
||||||
|
if [ "$t" == "sitltest-copter-tests2b" ]; then
|
||||||
|
run_autotest "Copter" "build.Copter" "test.CopterTests2b"
|
||||||
|
continue
|
||||||
|
fi
|
||||||
|
|
||||||
if [ "$t" == "sitltest-plane" ]; then
|
if [ "$t" == "sitltest-plane" ]; then
|
||||||
run_autotest "Plane" "build.Plane" "test.Plane"
|
run_autotest "Plane" "build.Plane" "test.Plane"
|
||||||
continue
|
continue
|
||||||
|
Loading…
Reference in New Issue
Block a user