LogAnalyzer: report skippedLines, cleaned up DataflashLog.read() error handling

This commit is contained in:
Andrew Chapman 2014-02-26 15:41:58 +01:00 committed by Andrew Tridgell
parent 2a406ac699
commit 1356d53e7b
3 changed files with 27 additions and 32 deletions

View File

@ -186,6 +186,7 @@ class DataflashLog:
filesizeKB = 0
durationSecs = 0
lineCount = 0
skippedLines = 0
def getCopterType(self):
if self.vehicleType != "ArduCopter":
@ -222,10 +223,8 @@ class DataflashLog:
#self.read(logfile, ignoreBadlines)
def read(self, logfile, ignoreBadlines=False):
'''returns True on successful log read (including bad lines if ignoreBadlines==True), False otherwise'''
'''returns on successful log read (including bad lines if ignoreBadlines==True), will throw an Exception otherwise'''
# TODO: dataflash log parsing code is *SUPER* hacky, should re-write more methodically
# TODO: fix error handling of logfile reading, return code vs exception, error message reporting
# TODO: report number of lines skipped during read
self.filename = logfile
f = open(self.filename, 'r')
lineNumber = 0
@ -239,8 +238,7 @@ class DataflashLog:
# first handle the log header lines
if line == " Ready to drive." or line == " Ready to FLY.":
continue
if line == "----------------------------------------":
#return False
if line == "----------------------------------------": # present in pre-3.0 logs
raise Exception("Log file seems to be in the older format (prior to self-describing logs), which isn't supported")
if len(tokens) == 1:
tokens2 = line.split(' ')
@ -261,6 +259,7 @@ class DataflashLog:
errorMsg = "Error parsing line %d of log file: %s" % (lineNumber, self.filename)
if ignoreBadlines:
print errorMsg + " (skipping line)"
self.skippedLines += 1
else:
raise Exception(errorMsg)
# now handle the non-log data stuff, format descriptions, params, etc
@ -300,6 +299,7 @@ class DataflashLog:
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))
if ignoreBadlines:
print errorMsg + " (skipping line)"
self.skippedLines += 1
continue
else:
raise Exception(errorMsg)
@ -311,9 +311,9 @@ class DataflashLog:
#print "Set data {%s,%s} for line %d to value %s, of type %c, stored at address %s" % (groupName, label, lineNumber, `value`, self.formats[groupName].types[index], hex(id(channel.dictData)))
channel.dictData[lineNumber] = value
channel.listData.append((lineNumber,value))
except:
print "Error parsing line %d of log file %s" % (lineNumber,self.filename)
return False
except Exception as e:
raise Exception("Error parsing line %d of log file %s - %s" % (lineNumber,self.filename,e.args[0]))
# gather some general stats about the log
self.lineCount = lineNumber
@ -330,5 +330,4 @@ class DataflashLog:
# TODO: calculate logging rate based on timestamps
return True

View File

@ -96,6 +96,8 @@ class TestSuite:
print 'Firmware Version: %s (%s)' % (self.logdata.firmwareVersion, self.logdata.firmwareHash)
print 'Hardware: %s' % self.logdata.hardwareType
print 'Free RAM: %s' % self.logdata.freeRAM
if self.logdata.skippedLines:
print "\nWARNING: %d malformed log lines skipped during read" % self.logdata.skippedLines
print '\n'
print "Test Results:"
@ -149,6 +151,7 @@ class TestSuite:
print >>xml, " <firmwarehash>" + self.logdata.firmwareHash + "</firmwarehash>"
print >>xml, " <hardwaretype>" + self.logdata.hardwareType + "</hardwaretype>"
print >>xml, " <freemem>" + `self.logdata.freeRAM` + "</freemem>"
print >>xml, " <skippedlines>" + `self.logdata.skippedLines` + "</skippedlines>"
print >>xml, "</header>"
# output parameters

View File

@ -2,15 +2,16 @@
<loganalysis>
<header>
<logfile>logs/robert_lefebvre_octo_PM.log</logfile>
<sizekb>302.744140625</sizekb>
<sizekb>302.7548828125</sizekb>
<sizelines>4750</sizelines>
<duration>0:02:35</duration>
<vehicletype>ArduCopter</vehicletype>
<coptertype>octo</coptertype>
<firmwareversion>V3.0.1</firmwareversion>
<firmwarehash></firmwarehash>
<firmwarehash>5c6503e2</firmwarehash>
<hardwaretype>APM 2</hardwaretype>
<freemem>1331</freemem>
<skippedlines>0</skippedlines>
</header>
<params>
<param name="RC7_REV" value="1.0" />
@ -287,12 +288,6 @@
<param name="RC1_TRIM" value="1524.0" />
</params>
<results>
<result>
<name>Balance/Twist</name>
<status>PASS</status>
<message></message>
<extrafeedback></extrafeedback>
</result>
<result>
<name>Brownout</name>
<status>PASS</status>
@ -305,6 +300,12 @@
<message></message>
<extrafeedback></extrafeedback>
</result>
<result>
<name>Dupe Log Data</name>
<status>PASS</status>
<message></message>
<extrafeedback></extrafeedback>
</result>
<result>
<name>Empty</name>
<status>PASS</status>
@ -327,25 +328,17 @@
</result>
<result>
<name>Parameters</name>
<status>FAIL</status>
<message>Bad parameters found:</message>
<extrafeedback>THR_MID set to 300.0, expecting less than 300
</extrafeedback>
<data>(test data will be embeded here at some point)</data>
</result>
<result>
<name>Performance</name>
<status>FAIL</status>
<message>14 slow loop lines found, up to 18% (line 2983)</message>
<extrafeedback></extrafeedback>
<data>(test data will be embeded here at some point)</data>
</result>
<result>
<name>Pitch/Roll</name>
<status>PASS</status>
<message></message>
<extrafeedback></extrafeedback>
</result>
<result>
<name>PM</name>
<status>FAIL</status>
<message>14 slow loop lines found, max 18.56% on line 2983</message>
<extrafeedback></extrafeedback>
<data>(test data will be embeded here at some point)</data>
</result>
<result>
<name>Underpowered</name>
<status>PASS</status>