|
|
@ -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 = "" |
|
|
|