mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
LogAnalyzer: TestPitchRollCoupling add mode ""
- "" is a valid alias for AUTOTUNE
This commit is contained in:
parent
d50d5b8f24
commit
6ce0dbf3b3
@ -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
|
# 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
|
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
|
||||||
manualSegments = [] # list of (startLine,endLine) pairs
|
manualSegments = [] # list of (startLine,endLine) pairs
|
||||||
orderedModes = collections.OrderedDict(sorted(logdata.modeChanges.items(), key=lambda t: t[0]))
|
orderedModes = collections.OrderedDict(sorted(logdata.modeChanges.items(), key=lambda t: t[0]))
|
||||||
|
Loading…
Reference in New Issue
Block a user