LogAnalyzer: Adding HYBRID mode to LogAnalyzer.

This commit is contained in:
Linus Casassa 2014-06-27 20:02:05 -04:00 committed by Craig Elder
parent 03770c4d34
commit ce0efdb7d2

View File

@ -26,7 +26,7 @@ class TestPitchRollCoupling(Test):
return return
# figure out where each mode begins and ends, so we can treat auto and manual modes differently and ignore acro/tune modes # 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"] # use NTUN DRol+DPit 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 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 autoSegments = [] # list of (startLine,endLine) pairs