From 81fcf4bda70f7cf4988dd4fa48cc32d25209c704 Mon Sep 17 00:00:00 2001 From: Andrew Chapman Date: Wed, 26 Feb 2014 20:22:22 +0100 Subject: [PATCH] LogAnalyzer: combined statusMessage and extraFeedback --- Tools/LogAnalyzer/DataflashLog.py | 6 +++--- Tools/LogAnalyzer/LogAnalyzer.py | 23 +++++++++------------- Tools/LogAnalyzer/example_output.xml | 11 ----------- Tools/LogAnalyzer/tests/TestCompass.py | 23 +++++++++++----------- Tools/LogAnalyzer/tests/TestGPSGlitch.py | 2 +- Tools/LogAnalyzer/tests/TestParams.py | 12 +++++------ Tools/LogAnalyzer/tests/TestPerformance.py | 4 ++-- 7 files changed, 32 insertions(+), 49 deletions(-) diff --git a/Tools/LogAnalyzer/DataflashLog.py b/Tools/LogAnalyzer/DataflashLog.py index 853ef220d4..da245ae908 100644 --- a/Tools/LogAnalyzer/DataflashLog.py +++ b/Tools/LogAnalyzer/DataflashLog.py @@ -261,7 +261,7 @@ class DataflashLog: print errorMsg + " (skipping line)" self.skippedLines += 1 else: - raise Exception(errorMsg) + raise Exception("") # now handle the non-log data stuff, format descriptions, params, etc elif tokens[0] == "FMT": format = None @@ -270,7 +270,7 @@ class DataflashLog: elif len(tokens) == 5: # some logs have FMT STRT with no labels format = Format(tokens[1],tokens[2],tokens[3],tokens[4],"") else: - raise Exception("FMT error on line %d, nTokens: %d" % (lineNumber, len(tokens))) + raise Exception("FMT error, nTokens: %d" % len(tokens)) #print format # TEMP self.formats[tokens[3]] = format elif tokens[0] == "PARM": @@ -296,7 +296,7 @@ class DataflashLog: self.channels[groupName][label] = Channel() # check the number of tokens matches between the line and what we're expecting from the FMT definition if (len(tokens2)-1) != len(self.formats[groupName].labels): - errorMsg = "Error on line %d of log file: %s, %s line's value count (%d) not matching FMT specification (%d)" % (lineNumber, self.filename, groupName, len(tokens2)-1, len(self.formats[groupName].labels)) + errorMsg = "%s line's value count (%d) not matching FMT specification (%d) on line %d" % (groupName, len(tokens2)-1, len(self.formats[groupName].labels), lineNumber) if ignoreBadlines: print errorMsg + " (skipping line)" self.skippedLines += 1 diff --git a/Tools/LogAnalyzer/LogAnalyzer.py b/Tools/LogAnalyzer/LogAnalyzer.py index 40bdb9ff7b..5855a44ae8 100755 --- a/Tools/LogAnalyzer/LogAnalyzer.py +++ b/Tools/LogAnalyzer/LogAnalyzer.py @@ -14,8 +14,6 @@ # - copter+plane use 'V' in their vehicle type/version/build line, rover uses lower case 'v'. Copter+Rover give a build number, plane does not # - CTUN.ThrOut on copter is 0-1000, on plane+rover it is 0-100 -# TODO - unify result statusMessage and extraOutput. simple tests set statusMessage, complex ones append to it with newlines - import DataflashLog @@ -36,7 +34,6 @@ class TestResult: PASS, FAIL, WARN, UNKNOWN, NA = range(5) status = None statusMessage = "" - extraFeedback = "" class Test: @@ -104,23 +101,25 @@ class TestSuite: for test in self.tests: if not test.enable: continue + statusMessageFirstLine = test.result.statusMessage.strip('\n\r').split('\n')[0] + statusMessageExtra = test.result.statusMessage.strip('\n\r').split('\n')[1:] execTime = "" if outputStats: execTime = " (%.2fms)" % (test.execTime) if test.result.status == TestResult.StatusType.PASS: - print " %20s: PASS %-50s%s" % (test.name, test.result.statusMessage,execTime) + print " %20s: PASS %-55s%s" % (test.name, statusMessageFirstLine, execTime) elif test.result.status == TestResult.StatusType.FAIL: - print " %20s: FAIL %-50s%s [GRAPH]" % (test.name, test.result.statusMessage,execTime) + print " %20s: FAIL %-55s%s [GRAPH]" % (test.name, statusMessageFirstLine, execTime) elif test.result.status == TestResult.StatusType.WARN: - print " %20s: WARN %-50s%s [GRAPH]" % (test.name, test.result.statusMessage,execTime) + print " %20s: WARN %-55s%s [GRAPH]" % (test.name, statusMessageFirstLine, execTime) elif test.result.status == TestResult.StatusType.NA: # skip any that aren't relevant for this vehicle/hardware/etc continue else: - print " %20s: UNKNOWN %-50s%s" % (test.name, test.result.statusMessage,execTime) - if test.result.extraFeedback: - for line in test.result.extraFeedback.strip().split('\n'): - print " %29s %s" % ("",line) + print " %20s: UNKNOWN %-55s%s" % (test.name, statusMessageFirstLine, execTime) + #if statusMessageExtra: + for line in statusMessageExtra: + print " %29s %s" % ("",line) print '\n' print 'The Log Analyzer is currently BETA code.\nFor any support or feedback on the log analyzer please email Andrew Chapman (amchapman@gmail.com)' @@ -173,18 +172,15 @@ class TestSuite: print >>xml, " " + test.name + "" print >>xml, " PASS" print >>xml, " " + test.result.statusMessage + "" - print >>xml, " " + test.result.extraFeedback + "" elif test.result.status == TestResult.StatusType.FAIL: print >>xml, " " + test.name + "" print >>xml, " FAIL" print >>xml, " " + test.result.statusMessage + "" - print >>xml, " " + test.result.extraFeedback + "" print >>xml, " (test data will be embeded here at some point)" elif test.result.status == TestResult.StatusType.WARN: print >>xml, " " + test.name + "" print >>xml, " WARN" print >>xml, " " + test.result.statusMessage + "" - print >>xml, " " + test.result.extraFeedback + "" print >>xml, " (test data will be embeded here at some point)" elif test.result.status == TestResult.StatusType.NA: # skip any that aren't relevant for this vehicle/hardware/etc @@ -193,7 +189,6 @@ class TestSuite: print >>xml, " " + test.name + "" print >>xml, " UNKNOWN" print >>xml, " " + test.result.statusMessage + "" - print >>xml, " " + test.result.extraFeedback + "" print >>xml, " " print >>xml, "" diff --git a/Tools/LogAnalyzer/example_output.xml b/Tools/LogAnalyzer/example_output.xml index 8b820d2dde..c6341cc1a8 100644 --- a/Tools/LogAnalyzer/example_output.xml +++ b/Tools/LogAnalyzer/example_output.xml @@ -292,70 +292,59 @@ Brownout PASS - Compass PASS - Dupe Log Data PASS - Empty PASS - Event/Failsafe FAIL ERR found: GPS - (test data will be embeded here at some point) GPS WARN Min satellites: 6, Max HDop: 4.68 - (test data will be embeded here at some point) Parameters PASS - PM FAIL 14 slow loop lines found, max 18.56% on line 2983 - (test data will be embeded here at some point) Underpowered PASS - VCC PASS - Vibration UNKNOWN No IMU log data - diff --git a/Tools/LogAnalyzer/tests/TestCompass.py b/Tools/LogAnalyzer/tests/TestCompass.py index 401bd5a30c..5eb132df23 100644 --- a/Tools/LogAnalyzer/tests/TestCompass.py +++ b/Tools/LogAnalyzer/tests/TestCompass.py @@ -12,7 +12,7 @@ class TestCompass(Test): self.result = TestResult() self.result.status = TestResult.StatusType.PASS - # quick test that compass offset parameters are within recommended range (+/- 150) + # test that compass offset parameters are within recommended range (+/- 150) maxOffset = 150 if logdata.hardwareType == "PX4": maxOffset = 250 # Pixhawks have their offsets scaled larger @@ -22,33 +22,32 @@ class TestCompass(Test): #print "MAG params: %.2f %.2f %.2f" % (compassOfsX,compassOfsY,compassOfsZ) if abs(compassOfsX) > maxOffset or abs(compassOfsY) > maxOffset or abs(compassOfsZ) > maxOffset: self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = "Large compass off params (X:%.2f, Y:%.2f, Z:%.2f)" % (compassOfsX,compassOfsY,compassOfsZ) + self.result.statusMessage = "Large compass off params (X:%.2f, Y:%.2f, Z:%.2f)\n" % (compassOfsX,compassOfsY,compassOfsZ) # check for excessive compass offsets using MAG data if present (it can change during flight is compass learn is on) if "MAG" in logdata.channels: - err = False - #print "MAG min/max xyz... %.2f %.2f %.2f %.2f %.2f %.2f " % (logdata.channels["MAG"]["OfsX"].min(), logdata.channels["MAG"]["OfsX"].max(), logdata.channels["MAG"]["OfsY"].min(), logdata.channels["MAG"]["OfsY"].min(), logdata.channels["MAG"]["OfsZ"].min(), logdata.channels["MAG"]["OfsZ"].max()) + errMsg = "" if logdata.channels["MAG"]["OfsX"].max() > maxOffset: - self.result.extraFeedback = self.result.extraFeedback + "X: %.2f\n" % logdata.channels["MAG"]["OfsX"].max() + errMsg = errMsg + "\nX: %.2f\n" % logdata.channels["MAG"]["OfsX"].max() err = True if logdata.channels["MAG"]["OfsX"].min() < -maxOffset: - self.result.extraFeedback = self.result.extraFeedback + "X: %.2f\n" % logdata.channels["MAG"]["OfsX"].min() + errMsg = errMsg + "\nX: %.2f\n" % logdata.channels["MAG"]["OfsX"].min() err = True if logdata.channels["MAG"]["OfsY"].max() > maxOffset: - self.result.extraFeedback = self.result.extraFeedback + "Y: %.2f\n" % logdata.channels["MAG"]["OfsY"].max() + errMsg = errMsg + "\nY: %.2f\n" % logdata.channels["MAG"]["OfsY"].max() err = True if logdata.channels["MAG"]["OfsY"].min() < -maxOffset: - self.result.extraFeedback = self.result.extraFeedback + "Y: %.2f\n" % logdata.channels["MAG"]["OfsY"].min() + errMsg = errMsg + "\nY: %.2f\n" % logdata.channels["MAG"]["OfsY"].min() err = True if logdata.channels["MAG"]["OfsZ"].max() > maxOffset: - self.result.extraFeedback = self.result.extraFeedback + "Z: %.2f\n" % logdata.channels["MAG"]["OfsZ"].max() + errMsg = errMsg + "\nZ: %.2f\n" % logdata.channels["MAG"]["OfsZ"].max() err = True if logdata.channels["MAG"]["OfsZ"].min() < -maxOffset: - self.result.extraFeedback = self.result.extraFeedback + "Z: %.2f\n" % logdata.channels["MAG"]["OfsZ"].min() + errMsg = errMsg + "\nZ: %.2f\n" % logdata.channels["MAG"]["OfsZ"].min() err = True - if err: + if errMsg: self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = "Large compass offset in MAG data" + self.result.statusMessage = self.result.statusMessage + "Large compass offset in MAG data:" + errMsg # TODO: check for compass/throttle interference. Need to add mag_field to logging, or calc our own from MAG data if present # TODO: can we derive a compassmot percentage from the params? Fail if >30%? diff --git a/Tools/LogAnalyzer/tests/TestGPSGlitch.py b/Tools/LogAnalyzer/tests/TestGPSGlitch.py index 7c3a745a07..2e3d0ddb73 100644 --- a/Tools/LogAnalyzer/tests/TestGPSGlitch.py +++ b/Tools/LogAnalyzer/tests/TestGPSGlitch.py @@ -42,7 +42,7 @@ class TestGPSGlitch(Test): foundBadHDopFail = logdata.channels["GPS"]["HDop"].max() > maxHDopFAIL satsMsg = "Min satellites: %s, Max HDop: %s" % (logdata.channels["GPS"]["NSats"].min(), logdata.channels["GPS"]["HDop"].max()) if gpsGlitchCount: - self.result.extraFeedback = satsMsg + self.result.statusMessage = self.result.statusMessage + "\n" + satsMsg if foundBadSatsFail or foundBadHDopFail: if not gpsGlitchCount: self.result.status = TestResult.StatusType.FAIL diff --git a/Tools/LogAnalyzer/tests/TestParams.py b/Tools/LogAnalyzer/tests/TestParams.py index e2d13680d6..ee99780e07 100644 --- a/Tools/LogAnalyzer/tests/TestParams.py +++ b/Tools/LogAnalyzer/tests/TestParams.py @@ -16,17 +16,17 @@ class TestParams(Test): value = logdata.parameters[paramName] if value != expectedValue: self.result.status = TestResult.StatusType.FAIL - self.result.extraFeedback = self.result.extraFeedback + "%s set to %s, expecting %s\n" % (paramName, `value`, `expectedValue`) + self.result.statusMessage = self.result.statusMessage + "%s set to %s, expecting %s\n" % (paramName, `value`, `expectedValue`) def __checkParamIsLessThan(self, paramName, maxValue, logdata): value = logdata.parameters[paramName] if value >= maxValue: self.result.status = TestResult.StatusType.FAIL - self.result.extraFeedback = self.result.extraFeedback + "%s set to %s, expecting less than %s\n" % (paramName, `value`, `maxValue`) + self.result.statusMessage = self.result.statusMessage + "%s set to %s, expecting less than %s\n" % (paramName, `value`, `maxValue`) def __checkParamIsMoreThan(self, paramName, minValue, logdata): value = logdata.parameters[paramName] if value <= minValue: self.result.status = TestResult.StatusType.FAIL - self.result.extraFeedback = self.result.extraFeedback + "%s set to %s, expecting less than %s\n" % (paramName, `value`, `minValue`) + self.result.statusMessage = self.result.statusMessage + "%s set to %s, expecting less than %s\n" % (paramName, `value`, `minValue`) def run(self, logdata): @@ -37,9 +37,9 @@ class TestParams(Test): for name,value in logdata.parameters.iteritems(): if math.isnan(value): self.result.status = TestResult.StatusType.FAIL - self.result.extraFeedback = self.result.extraFeedback + name + " is NaN\n" + self.result.statusMessage = self.result.statusMessage + name + " is NaN\n" - # add parameter checks below using the helper functions, any failures will trigger a FAIL status and accumulate info in extraFeedback + # add parameter checks below using the helper functions, any failures will trigger a FAIL status and accumulate info in statusMessage # if more complex checking or correlations are required you can access parameter values directly using the logdata.parameters[paramName] dict if logdata.vehicleType == "ArduCopter": self.__checkParamIsEqual ("MAG_ENABLE", 1, logdata) @@ -55,4 +55,4 @@ class TestParams(Test): pass if self.result.status == TestResult.StatusType.FAIL: - self.result.statusMessage = "Bad parameters found:" + self.result.statusMessage = "Bad parameters found:\n" + self.result.statusMessage diff --git a/Tools/LogAnalyzer/tests/TestPerformance.py b/Tools/LogAnalyzer/tests/TestPerformance.py index 1042f87015..51889a7088 100644 --- a/Tools/LogAnalyzer/tests/TestPerformance.py +++ b/Tools/LogAnalyzer/tests/TestPerformance.py @@ -59,5 +59,5 @@ class TestPerformance(Test): elif (maxPercentSlow > 6): self.result.status = TestResult.StatusType.WARN self.result.statusMessage = "%d slow loop lines found, max %.2f%% on line %d" % (slowLoopLineCount,maxPercentSlow,maxPercentSlowLine) - else: - self.result.extraFeedback = "" + +