LogAnalyzer: adding Roberts bad PM performance log

This commit is contained in:
Andrew Chapman 2014-01-30 02:01:43 -08:00 committed by Andrew Tridgell
parent 8d691c2a60
commit e0ada31872
5 changed files with 4771 additions and 18 deletions

View File

@ -128,11 +128,11 @@ class DataflashLog:
'''APM Dataflash log file reader and container class. Keep this simple, add more advanced or specific functions to DataflashLogHelper class''' '''APM Dataflash log file reader and container class. Keep this simple, add more advanced or specific functions to DataflashLogHelper class'''
filename = None filename = None
vehicleType = None # ArduCopter, ArduPlane, ArduRover, etc, verbatim as given by header vehicleType = "" # ArduCopter, ArduPlane, ArduRover, etc, verbatim as given by header
firmwareVersion = None firmwareVersion = ""
firmwareHash = "" firmwareHash = ""
freeRAM = None freeRAM = 0
hardwareType = None # APM 1, APM 2, PX4, MPNG, etc What is VRBrain? BeagleBone, etc? Needs more testing hardwareType = "" # APM 1, APM 2, PX4, MPNG, etc What is VRBrain? BeagleBone, etc? Needs more testing
formats = {} # name -> Format formats = {} # name -> Format
parameters = {} # token -> value parameters = {} # token -> value
@ -140,9 +140,9 @@ class DataflashLog:
modeChanges = {} # lineNum -> (mode,value) modeChanges = {} # lineNum -> (mode,value)
channels = {} # lineLabel -> {dataLabel:Channel} channels = {} # lineLabel -> {dataLabel:Channel}
filesizeKB = None filesizeKB = 0
durationSecs = 0 durationSecs = 0
lineCount = None lineCount = 0
def getCopterType(self): def getCopterType(self):
if self.vehicleType != "ArduCopter": if self.vehicleType != "ArduCopter":

View File

@ -120,8 +120,7 @@ class TestSuite:
print '\n' print '\n'
def outputXML(self, xmlFile): def outputXML(self, xmlFile):
# TODO: implement XML output # open the file for writing
xml = None xml = None
try: try:
xml = open(xmlFile, 'w') xml = open(xmlFile, 'w')
@ -129,10 +128,10 @@ class TestSuite:
sys.stderr.write("Error opening output xml file: %s" % xmlFile) sys.stderr.write("Error opening output xml file: %s" % xmlFile)
sys.exit(1) sys.exit(1)
print >>xml, "<?xml version=\"1.0\" encoding=\"UTF-8\"?>"
print >>xml, "<loganalysis>"
# output header info # output header info
print >>xml, "<?xml version=\"1.0\" encoding=\"UTF-8\"?>"
print >>xml, "<loganalysis>"
print >>xml, "<header>" print >>xml, "<header>"
print >>xml, " <logfile>" + self.logfile + "</logfile>" print >>xml, " <logfile>" + self.logfile + "</logfile>"
print >>xml, " <sizekb>" + `self.logdata.filesizeKB` + "</sizekb>" print >>xml, " <sizekb>" + `self.logdata.filesizeKB` + "</sizekb>"

File diff suppressed because it is too large Load Diff

View File

@ -43,8 +43,8 @@ class TestParams(Test):
if logdata.vehicleType == "ArduCopter": if logdata.vehicleType == "ArduCopter":
self.__checkParamIsEqual ("MAG_ENABLE", 1, logdata) self.__checkParamIsEqual ("MAG_ENABLE", 1, logdata)
self.__checkParamIsLessThan("THR_MIN", 200, logdata) self.__checkParamIsLessThan("THR_MIN", 200, logdata)
self.__checkParamIsLessThan("THR_MID", 650, logdata) self.__checkParamIsLessThan("THR_MID", 701, logdata)
self.__checkParamIsMoreThan("THR_MID", 300, logdata) self.__checkParamIsMoreThan("THR_MID", 299, logdata)
# TODO: add more parameter tests, these are just an example... # TODO: add more parameter tests, these are just an example...
elif logdata.vehicleType == "ArduPlane": elif logdata.vehicleType == "ArduPlane":
# TODO: add parameter checks for plane... # TODO: add parameter checks for plane...

View File

@ -30,8 +30,12 @@ class TestPerformance(Test):
# ignoreMaxTLines.append(maxT[0]) # ignoreMaxTLines.append(maxT[0])
# armingLines.pop(0) # armingLines.pop(0)
if "PM" not in logdata.channels:
self.result.status = TestResult.StatusType.UNKNOWN
self.result.statusMessage = "No PM log data"
return
# check for slow loops, i.e. NLon greater than 5% of NLoop # check for slow loops, i.e. NLon greater than 6% of NLoop
maxPercentSlow = 0 maxPercentSlow = 0
maxPercentSlowLine = 0 maxPercentSlowLine = 0
slowLoopLineCount = 0 slowLoopLineCount = 0
@ -40,18 +44,18 @@ class TestPerformance(Test):
(line, nLoop) = logdata.channels["PM"]["NLoop"].listData[i] (line, nLoop) = logdata.channels["PM"]["NLoop"].listData[i]
(line, maxT) = logdata.channels["PM"]["MaxT"].listData[i] (line, maxT) = logdata.channels["PM"]["MaxT"].listData[i]
percentSlow = (nLon / float(nLoop)) * 100 percentSlow = (nLon / float(nLoop)) * 100
if percentSlow > 5.0: if percentSlow > 6.0:
slowLoopLineCount = slowLoopLineCount + 1 slowLoopLineCount = slowLoopLineCount + 1
if percentSlow > maxPercentSlow: if percentSlow > maxPercentSlow:
maxPercentSlow = percentSlow maxPercentSlow = percentSlow
maxPercentSlowLine = line maxPercentSlowLine = line
#if (maxT > 13000) and line not in ignoreMaxTLines: #if (maxT > 13000) and line not in ignoreMaxTLines:
# print "MaxT of %d detected on line %d" % (maxT,line) # print "MaxT of %d detected on line %d" % (maxT,line)
if (maxPercentSlow > 10) or (slowLoopLineCount > 5): if (maxPercentSlow > 10) or (slowLoopLineCount > 6):
self.result.status = TestResult.StatusType.FAIL self.result.status = TestResult.StatusType.FAIL
self.result.statusMessage = "%d slow loop lines found, max %d%% on line %d" % (slowLoopLineCount,maxPercentSlow,maxPercentSlowLine) self.result.statusMessage = "%d slow loop lines found, max %.2f%% on line %d" % (slowLoopLineCount,maxPercentSlow,maxPercentSlowLine)
elif (maxPercentSlow > 5): elif (maxPercentSlow > 6):
self.result.status = TestResult.StatusType.WARN self.result.status = TestResult.StatusType.WARN
self.result.statusMessage = "%d slow loop lines found, max %d%% on line %d" % (slowLoopLineCount,maxPercentSlow,maxPercentSlowLine) self.result.statusMessage = "%d slow loop lines found, max %.2f%% on line %d" % (slowLoopLineCount,maxPercentSlow,maxPercentSlowLine)
else: else:
self.result.extraFeedback = "" self.result.extraFeedback = ""