mirror of https://github.com/ArduPilot/ardupilot
autotest: except QRTL/QLAND from airmode tests due to non-armability
The test wasn't checking the return value for arming, so of course the motors weren't spinning.... now we've fixed the checked-for-arming thing these two modes were failing.
This commit is contained in:
parent
8fc6e98900
commit
0d4bee8f7b
|
@ -177,7 +177,8 @@ class AutoTestQuadPlane(AutoTest):
|
||||||
ahrs_trim_x = self.get_parameter("AHRS_TRIM_X")
|
ahrs_trim_x = self.get_parameter("AHRS_TRIM_X")
|
||||||
self.set_parameter("AHRS_TRIM_X", math.radians(-60))
|
self.set_parameter("AHRS_TRIM_X", math.radians(-60))
|
||||||
self.wait_roll(60, 1)
|
self.wait_roll(60, 1)
|
||||||
# test all modes except QSTABILIZE, QACRO, AUTO and QAUTOTUNE
|
# test all modes except QSTABILIZE, QACRO, AUTO and QAUTOTUNE and QLAND and QRTL
|
||||||
|
# QRTL and QLAND aren't tested because we can't arm in that mode
|
||||||
for mode in (
|
for mode in (
|
||||||
'ACRO',
|
'ACRO',
|
||||||
'AUTOTUNE',
|
'AUTOTUNE',
|
||||||
|
@ -189,9 +190,7 @@ class AutoTestQuadPlane(AutoTest):
|
||||||
'GUIDED',
|
'GUIDED',
|
||||||
'LOITER',
|
'LOITER',
|
||||||
'QHOVER',
|
'QHOVER',
|
||||||
'QLAND',
|
|
||||||
'QLOITER',
|
'QLOITER',
|
||||||
'QRTL',
|
|
||||||
'RTL',
|
'RTL',
|
||||||
'STABILIZE',
|
'STABILIZE',
|
||||||
'TRAINING',
|
'TRAINING',
|
||||||
|
|
Loading…
Reference in New Issue