From 0d4bee8f7b5b8b107781306e1be34a058723d972 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 13 Aug 2021 09:49:35 +1000 Subject: [PATCH] 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. --- Tools/autotest/quadplane.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index e5a69e133f..6d7ca34089 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -177,7 +177,8 @@ class AutoTestQuadPlane(AutoTest): ahrs_trim_x = self.get_parameter("AHRS_TRIM_X") self.set_parameter("AHRS_TRIM_X", math.radians(-60)) 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 ( 'ACRO', 'AUTOTUNE', @@ -189,9 +190,7 @@ class AutoTestQuadPlane(AutoTest): 'GUIDED', 'LOITER', 'QHOVER', - 'QLAND', 'QLOITER', - 'QRTL', 'RTL', 'STABILIZE', 'TRAINING',