mirror of https://github.com/ArduPilot/ardupilot
LogAnalyzer: added unit test, started moving from dictData to listData
added unit test, started moving from dictData to listData, cancelled pre-3.0 log reading, separated DataflashLog constructor and read() call
This commit is contained in:
parent
d6b091c39f
commit
90f07aae61
|
@ -4,9 +4,6 @@
|
|||
# Initial code by Andrew Chapman (chapman@skymount.com), 16th Jan 2014
|
||||
#
|
||||
|
||||
# TODO: log reading needs to be much more robust, only compatible with AC3.0.1-AC3.1 logs at this point, try to be compatible at least back to AC2.9.1, and APM:Plane too (skipping copter-only tests)
|
||||
# TODO: rethink data storage, dictionaries are good for specific line lookups, but we don't end up doing a lot of that
|
||||
|
||||
import pprint # temp
|
||||
import collections
|
||||
import os
|
||||
|
@ -32,9 +29,12 @@ class Format:
|
|||
|
||||
class Channel:
|
||||
'''storage for a single stream of data, i.e. all GPS.RelAlt values'''
|
||||
# TODO: store data as a curve so we can more easily interpolate and sample the slope
|
||||
|
||||
# TODO: rethink data storage, but do regression test suite first before refactoring it
|
||||
# TODO: store data as a curve so we can more easily interpolate and sample the slope?
|
||||
dictData = None # dict of linenum->value # store dupe data in dict and list for now, until we decide which is the better way to go
|
||||
listData = None # list of (linenum,value)
|
||||
|
||||
def __init__(self):
|
||||
self.dictData = {}
|
||||
self.listData = []
|
||||
|
@ -73,6 +73,28 @@ class Channel:
|
|||
weight = (lineNumber-prevValueLine) / float(nextValueLine-prevValueLine)
|
||||
return ((weight*prevValue) + ((1-weight)*nextValue))
|
||||
|
||||
# class LogIterator:
|
||||
# '''Smart iterator that can move through a log by line number and maintain an index into the nearest values of all data channels'''
|
||||
|
||||
# iterators = [] # (lineLabel, dataLabel) -> listIndex
|
||||
# logdata = None
|
||||
# currentLine = None
|
||||
|
||||
# def __init__(self, logdata):
|
||||
# self.logdata = logdata
|
||||
# self.currentLine = 0
|
||||
# for format in self.logdata.formats:
|
||||
# for label in format.labels:
|
||||
# iterators[(format,label)] = 0
|
||||
|
||||
# def __iter__(self):
|
||||
# return self
|
||||
|
||||
# def next(self):
|
||||
# pass
|
||||
|
||||
# def jump(self, lineNumber):
|
||||
# pass
|
||||
|
||||
class DataflashLogHelper:
|
||||
@staticmethod
|
||||
|
@ -189,16 +211,17 @@ class DataflashLog:
|
|||
else:
|
||||
raise Exception("Unknown value type of '%s' specified to __castToFormatType()" % valueType)
|
||||
|
||||
def __init__(self, logfile, ignoreBadlines=False):
|
||||
self.read(logfile, ignoreBadlines)
|
||||
#def __init__(self, logfile, ignoreBadlines=False):
|
||||
#self.read(logfile, ignoreBadlines)
|
||||
|
||||
def read(self, logfile, ignoreBadlines=False):
|
||||
'''returns True on successful log read (including bad lines if ignoreBadlines==True), False otherwise'''
|
||||
# TODO: dataflash log parsing code is *SUPER* hacky, should re-write more methodically
|
||||
# TODO: identify and bail on pre-3.0 logs, I think they're not worth supporting at this point
|
||||
|
||||
self.filename = logfile
|
||||
f = open(self.filename, 'r')
|
||||
lineNumber = 0
|
||||
copterLogPre3Header = False
|
||||
copterLogPre3Params = False
|
||||
knownHardwareTypes = ["APM", "PX4", "MPNG"]
|
||||
for line in f:
|
||||
lineNumber = lineNumber + 1
|
||||
|
@ -207,11 +230,11 @@ class DataflashLog:
|
|||
line = line.strip('\n\r')
|
||||
tokens = line.split(', ')
|
||||
# first handle the log header lines
|
||||
if copterLogPre3Header and line[0:15] == "SYSID_SW_MREV: ":
|
||||
copterLogPre3Header = False
|
||||
copterLogPre3Params = True
|
||||
if line == " Ready to drive." or line == " Ready to FLY.":
|
||||
continue
|
||||
if line == "----------------------------------------":
|
||||
#return False
|
||||
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(' ')
|
||||
if line == "":
|
||||
|
@ -222,18 +245,11 @@ class DataflashLog:
|
|||
self.freeRAM = int(tokens2[2])
|
||||
elif tokens2[0] in knownHardwareTypes:
|
||||
self.hardwareType = line # not sure if we can parse this more usefully, for now only need to report it back verbatim
|
||||
elif line[0:8] == "FW Ver: ":
|
||||
copterLogPre3Header = True
|
||||
elif copterLogPre3Header:
|
||||
pass # just skip over all that until we hit the PARM lines
|
||||
elif (len(tokens2) == 2 or len(tokens2) == 3) and tokens2[1][0].lower() == "v": # e.g. ArduCopter V3.1 (5c6503e2)
|
||||
self.vehicleType = tokens2[0]
|
||||
self.firmwareVersion = tokens2[1]
|
||||
if len(tokens2) == 3:
|
||||
self.firmwareHash = tokens2[2][1:-1]
|
||||
elif len(tokens2) == 2 and copterLogPre3Params:
|
||||
pName = tokens2[0]
|
||||
self.parameters[pName] = float(tokens2[1])
|
||||
else:
|
||||
errorMsg = "Error parsing line %d of log file: %s" % (lineNumber, self.filename)
|
||||
if ignoreBadlines:
|
||||
|
@ -264,7 +280,7 @@ class DataflashLog:
|
|||
else:
|
||||
raise Exception("Unknown log type for MODE line")
|
||||
# anything else must be the log data
|
||||
elif not copterLogPre3Header:
|
||||
else:
|
||||
groupName = tokens[0]
|
||||
tokens2 = line.split(', ')
|
||||
# first time seeing this type of log line, create the channel storage
|
||||
|
@ -272,8 +288,6 @@ class DataflashLog:
|
|||
self.channels[groupName] = {}
|
||||
for label in self.formats[groupName].labels:
|
||||
self.channels[groupName][label] = Channel()
|
||||
#print "Channel definition for group %s, data at address %s" % (groupName, hex(id(self.channels[groupName][label].dictData)))
|
||||
#pprint.pprint(self.channels[groupName]) # TEMP!!!
|
||||
# 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))
|
||||
|
@ -292,7 +306,7 @@ class DataflashLog:
|
|||
channel.listData.append((lineNumber,value))
|
||||
except:
|
||||
print "Error parsing line %d of log file %s" % (lineNumber,self.filename)
|
||||
raise
|
||||
return False
|
||||
|
||||
# gather some general stats about the log
|
||||
self.lineCount = lineNumber
|
||||
|
@ -306,3 +320,7 @@ class DataflashLog:
|
|||
lastTimeGPS = self.channels["GPS"][timeLabel].listData[-1][1]
|
||||
self.durationSecs = (lastTimeGPS-firstTimeGPS) / 1000
|
||||
|
||||
# TODO: calculate logging rate based on timestamps
|
||||
|
||||
return True
|
||||
|
||||
|
|
|
@ -121,7 +121,7 @@ class TestSuite:
|
|||
print " %20s %s" % ("",line)
|
||||
|
||||
print '\n'
|
||||
print 'The Log Analyzer is currently BETA code. For any support or feedback on the log analyzer please email Andrew Chapman (amchapman@gmail.com)'
|
||||
print 'The Log Analyzer is currently BETA code.\nFor any support or feedback on the log analyzer please email Andrew Chapman (amchapman@gmail.com)'
|
||||
print '\n'
|
||||
|
||||
def outputXML(self, xmlFile):
|
||||
|
@ -214,7 +214,8 @@ def main():
|
|||
|
||||
# load the log
|
||||
startTime = time.time()
|
||||
logdata = DataflashLog.DataflashLog(args.logfile.name, ignoreBadlines=args.skip_bad) # read log
|
||||
logdata = DataflashLog.DataflashLog()
|
||||
logdata.read(args.logfile.name, ignoreBadlines=args.skip_bad) # read log
|
||||
endTime = time.time()
|
||||
if args.profile:
|
||||
print "Log file read time: %.2f seconds" % (endTime-startTime)
|
||||
|
|
File diff suppressed because one or more lines are too long
|
@ -1,6 +1,6 @@
|
|||
1
|
||||
|
||||
ArduCopter V3.0.1
|
||||
ArduCopter V3.0.1 (5c6503e2)
|
||||
Free RAM: 1331
|
||||
APM 2
|
||||
FMT, 128, 89, FMT, BBnNZ, Type,Length,Name,Format
|
||||
|
|
|
@ -16,10 +16,8 @@ class TestBrownout(Test):
|
|||
if "EV" in logdata.channels:
|
||||
# step through the arm/disarm events in order, to see if they're symmetrical
|
||||
# note: it seems landing detection isn't robust enough to rely upon here, so we'll only consider arm+disarm, not takeoff+land
|
||||
evData = logdata.channels["EV"]["Id"]
|
||||
orderedEVData = collections.OrderedDict(sorted(evData.dictData.items(), key=lambda t: t[0]))
|
||||
isArmed = False
|
||||
for line,ev in orderedEVData.iteritems():
|
||||
for line,ev in logdata.channels["EV"]["Id"].listData:
|
||||
if ev == 10:
|
||||
isArmed = True
|
||||
elif ev == 11:
|
||||
|
|
|
@ -15,10 +15,10 @@ class TestEvents(Test):
|
|||
errors = set()
|
||||
|
||||
if "ERR" in logdata.channels:
|
||||
errLines = sorted(logdata.channels["ERR"]["Subsys"].dictData.keys())
|
||||
for line in errLines:
|
||||
subSys = logdata.channels["ERR"]["Subsys"].dictData[line]
|
||||
eCode = logdata.channels["ERR"]["ECode"].dictData[line]
|
||||
assert(len(logdata.channels["ERR"]["Subsys"].listData) == len(logdata.channels["ERR"]["ECode"].listData))
|
||||
for i in range(len(logdata.channels["ERR"]["Subsys"].listData)):
|
||||
subSys = logdata.channels["ERR"]["Subsys"].listData[i][1]
|
||||
eCode = logdata.channels["ERR"]["ECode"].listData[i][1]
|
||||
if subSys == 2 and (eCode == 1):
|
||||
errors.add("PPM")
|
||||
elif subSys == 3 and (eCode == 1 or eCode == 2):
|
||||
|
@ -40,7 +40,7 @@ class TestEvents(Test):
|
|||
elif subSys == 12 and (eCode == 1):
|
||||
errors.add("CRASH")
|
||||
|
||||
if len(errors) > 0:
|
||||
if errors:
|
||||
if len(errors) == 1 and "FENCE" in errors:
|
||||
self.result.status = TestResult.StatusType.WARN
|
||||
else:
|
||||
|
|
|
@ -17,12 +17,9 @@ class TestPerformance(Test):
|
|||
return
|
||||
|
||||
# NOTE: we'll ignore MaxT altogether for now, it seems there are quite regularly one or two high values in there, even ignoring the ones expected after arm/disarm events
|
||||
|
||||
# gather info on arm/disarm lines, we will ignore the MaxT data from the first line found after each of these
|
||||
# armingLines = []
|
||||
# evData = logdata.channels["EV"]["Id"]
|
||||
# orderedEVData = collections.OrderedDict(sorted(evData.dictData.items(), key=lambda t: t[0]))
|
||||
# for line,ev in orderedEVData.iteritems():
|
||||
# for line,ev in logdata.channels["EV"]["Id"].listData:
|
||||
# if (ev == 10) or (ev == 11):
|
||||
# armingLines.append(line)
|
||||
# ignoreMaxTLines = []
|
||||
|
|
|
@ -14,6 +14,7 @@ class TestUnderpowered(Test):
|
|||
|
||||
if logdata.vehicleType != "ArduCopter":
|
||||
self.result.status = TestResult.StatusType.NA
|
||||
return
|
||||
|
||||
if not "CTUN" in logdata.channels:
|
||||
self.result.status = TestResult.StatusType.UNKNOWN
|
||||
|
|
Loading…
Reference in New Issue