From 6ce0dbf3b3d73c7af35f38ca3926daa18481c7df Mon Sep 17 00:00:00 2001 From: Markus Koetter Date: Fri, 4 Jul 2014 15:41:25 +0200 Subject: [PATCH] LogAnalyzer: TestPitchRollCoupling add mode "" - "" is a valid alias for AUTOTUNE --- Tools/LogAnalyzer/tests/TestPitchRollCoupling.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py b/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py index 0bc2fb5274..e7fe9b3b24 100644 --- a/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py +++ b/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py @@ -28,7 +28,7 @@ class TestPitchRollCoupling(Test): # figure out where each mode begins and ends, so we can treat auto and manual modes differently and ignore acro/tune modes autoModes = ["RTL","AUTO","LAND","LOITER","GUIDED","CIRCLE","OF_LOITER","HYBRID"] # use NTUN DRol+DPit manualModes = ["STABILIZE","DRIFT","ALTHOLD","ALT_HOLD"] # use CTUN RollIn/DesRoll + PitchIn/DesPitch - ignoreModes = ["ACRO","SPORT","FLIP","AUTOTUNE"] # ignore data from these modes + ignoreModes = ["ACRO","SPORT","FLIP","AUTOTUNE",""] # ignore data from these modes autoSegments = [] # list of (startLine,endLine) pairs manualSegments = [] # list of (startLine,endLine) pairs orderedModes = collections.OrderedDict(sorted(logdata.modeChanges.items(), key=lambda t: t[0]))