mirror of https://github.com/ArduPilot/ardupilot
Tools: split Plane tests into tests1a and tests1b
This commit is contained in:
parent
c330e8e824
commit
653aff7f8a
|
@ -6290,6 +6290,13 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
ret = []
|
||||
ret.extend(self.tests1a())
|
||||
ret.extend(self.tests1b())
|
||||
return ret
|
||||
|
||||
def tests1a(self):
|
||||
ret = []
|
||||
ret = super(AutoTestPlane, self).tests()
|
||||
ret.extend([
|
||||
self.AuxModeSwitch,
|
||||
|
@ -6347,6 +6354,11 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.Soaring,
|
||||
self.Terrain,
|
||||
self.TerrainMission,
|
||||
])
|
||||
return ret
|
||||
|
||||
def tests1b(self):
|
||||
return [
|
||||
self.TerrainLoiter,
|
||||
self.VectorNavEAHRS,
|
||||
self.MicroStrainEAHRS5,
|
||||
|
@ -6424,8 +6436,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.MAV_CMD_EXTERNAL_WIND_ESTIMATE,
|
||||
self.GliderPullup,
|
||||
self.BadRollChannelDefined,
|
||||
])
|
||||
return ret
|
||||
]
|
||||
|
||||
def disabled_tests(self):
|
||||
return {
|
||||
|
@ -6434,3 +6445,13 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
"ClimbThrottleSaturation": "requires https://github.com/ArduPilot/ardupilot/pull/27106 to pass",
|
||||
"SetHomeAltChange": "https://github.com/ArduPilot/ardupilot/issues/5672",
|
||||
}
|
||||
|
||||
|
||||
class AutoTestPlaneTests1a(AutoTestPlane):
|
||||
def tests(self):
|
||||
return self.tests1a()
|
||||
|
||||
|
||||
class AutoTestPlaneTests1b(AutoTestPlane):
|
||||
def tests(self):
|
||||
return self.tests1b()
|
||||
|
|
|
@ -278,6 +278,9 @@ __bin_names = {
|
|||
"CopterTests2b": "arducopter",
|
||||
|
||||
"Plane": "arduplane",
|
||||
"PlaneTests1a": "arduplane",
|
||||
"PlaneTests1b": "arduplane",
|
||||
|
||||
"Rover": "ardurover",
|
||||
"Tracker": "antennatracker",
|
||||
"Helicopter": "arducopter-heli",
|
||||
|
@ -352,6 +355,8 @@ tester_class_map = {
|
|||
"test.CopterTests2a": arducopter.AutoTestCopterTests2a, # 8m23s
|
||||
"test.CopterTests2b": arducopter.AutoTestCopterTests2b, # 8m18s
|
||||
"test.Plane": arduplane.AutoTestPlane,
|
||||
"test.PlaneTests1a": arduplane.AutoTestPlaneTests1a,
|
||||
"test.PlaneTests1b": arduplane.AutoTestPlaneTests1b,
|
||||
"test.QuadPlane": quadplane.AutoTestQuadPlane,
|
||||
"test.Rover": rover.AutoTestRover,
|
||||
"test.BalanceBot": balancebot.AutoTestBalanceBot,
|
||||
|
@ -1112,6 +1117,9 @@ if __name__ == "__main__":
|
|||
'test.CopterTests2a',
|
||||
'test.CopterTests2b',
|
||||
|
||||
'test.PlaneTests1a',
|
||||
'test.PlaneTests1b',
|
||||
|
||||
'clang-scan-build',
|
||||
]
|
||||
|
||||
|
|
|
@ -135,8 +135,12 @@ for t in $CI_BUILD_TARGET; do
|
|||
run_autotest "Copter" "build.SITLPeriphUniversal" "test.CAN"
|
||||
continue
|
||||
fi
|
||||
if [ "$t" == "sitltest-plane" ]; then
|
||||
run_autotest "Plane" "build.Plane" "test.Plane"
|
||||
if [ "$t" == "sitltest-plane-tests1a" ]; then
|
||||
run_autotest "Plane" "build.Plane" "test.PlaneTests1a"
|
||||
continue
|
||||
fi
|
||||
if [ "$t" == "sitltest-plane-tests1b" ]; then
|
||||
run_autotest "Plane" "build.Plane" "test.PlaneTests1b"
|
||||
continue
|
||||
fi
|
||||
if [ "$t" == "sitltest-quadplane" ]; then
|
||||
|
|
Loading…
Reference in New Issue