From 6bd5ac78f51c99429271fb95cb60ee7d6a9f5117 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 30 Sep 2017 09:17:26 +1000 Subject: [PATCH] Tools: LogAnalyzer: fix string-method-on-int bug for unknown modes --- Tools/LogAnalyzer/DataflashLog.py | 10 ++++++++-- .../tests/TestPitchRollCoupling.py | 19 ++++++++++++++++--- 2 files changed, 24 insertions(+), 5 deletions(-) diff --git a/Tools/LogAnalyzer/DataflashLog.py b/Tools/LogAnalyzer/DataflashLog.py index d4f23f8978..9a6ed706ef 100644 --- a/Tools/LogAnalyzer/DataflashLog.py +++ b/Tools/LogAnalyzer/DataflashLog.py @@ -558,7 +558,12 @@ class DataflashLog(object): 13:'SPORT', 14:'FLIP', 15:'AUTOTUNE', - 16:'HYBRID',} + 16:'POSHOLD', + 17:'BRAKE', + 18:'THROW', + 19:'AVOID_ADSB', + 20:'GUIDED_NOGPS', + 21:'SMART_RTL'} if hasattr(e, 'ThrCrs'): self.modeChanges[lineNumber] = (modes[int(e.Mode)], e.ThrCrs) else: @@ -569,7 +574,8 @@ class DataflashLog(object): self.modeChanges[lineNumber] = (e.Mode, e.ThrCrs) else: # assume it has ModeNum: - self.modeChanges[lineNumber] = (e.Mode, e.ModeNum) + print("Unknown mode=%u" % e.ModeNum) + self.modeChanges[lineNumber] = (e.Mode, "mode=%u" % e.ModeNum) elif self.vehicleType in [VehicleType.Plane, VehicleType.Copter, VehicleType.Rover]: self.modeChanges[lineNumber] = (e.Mode, e.ModeNum) else: diff --git a/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py b/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py index aeef3cb872..8bc8e23113 100644 --- a/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py +++ b/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py @@ -28,9 +28,22 @@ class TestPitchRollCoupling(Test): return # 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","POSHOLD"] # use CTUN RollIn/DesRoll + PitchIn/DesPitch - ignoreModes = ["ACRO","SPORT","FLIP","AUTOTUNE",""] # ignore data from these modes + autoModes = ["RTL", + "AUTO", + "LAND", + "LOITER", + "GUIDED", + "CIRCLE", + "OF_LOITER", + "POSHOLD", + "BRAKE", + "AVOID_ADSB", + "GUIDED_NOGPS", + "SMARTRTL"] + # use CTUN RollIn/DesRoll + PitchIn/DesPitch + manualModes = ["STABILIZE", "DRIFT", "ALTHOLD", "ALT_HOLD", "POSHOLD"] + # ignore data from these modes: + ignoreModes = ["ACRO", "SPORT", "FLIP", "AUTOTUNE","", "THROW",] autoSegments = [] # list of (startLine,endLine) pairs manualSegments = [] # list of (startLine,endLine) pairs orderedModes = collections.OrderedDict(sorted(logdata.modeChanges.items(), key=lambda t: t[0]))