LogAnalyzer: added --verbose flag, added test for MAG interference

This commit is contained in:
Andrew Chapman 2014-03-03 18:46:17 +01:00 committed by Andrew Tridgell
parent 130a2dcb0b
commit 35830f928d
14 changed files with 82 additions and 28 deletions

View File

@ -42,7 +42,7 @@ class Test:
result = None # will be an instance of TestResult after being run
execTime = None
enable = True
def run(self, logdata):
def run(self, logdata, verbose=False):
pass
@ -68,8 +68,7 @@ class TestSuite:
# m = imp.load_source("m", dirName + '/tests/TestBadParams.py')
# self.tests.append(m.TestBadParams())
def run(self, logdata):
def run(self, logdata, verbose):
'''run all registered tests in a single call'''
self.logdata = logdata
self.logfile = logdata.filename
@ -77,7 +76,7 @@ class TestSuite:
# run each test in turn, gathering timing info
if test.enable:
startTime = time.time()
test.run(self.logdata) # RUN THE TEST
test.run(self.logdata, verbose) # RUN THE TEST
endTime = time.time()
test.execTime = 1000 * (endTime-startTime)
@ -208,6 +207,7 @@ def main():
parser.add_argument('-s', '--skip_bad', metavar='', action='store_const', const=True, help='skip over corrupt dataflash lines')
parser.add_argument('-e', '--empty', metavar='', action='store_const', const=True, help='run an initial check for an empty log')
parser.add_argument('-x', '--xml', type=str, metavar='XML file', nargs='?', const='', default='', help='write output to specified XML file')
parser.add_argument('-v', '--verbose', metavar='', action='store_const', const=True, help='verbose output')
args = parser.parse_args()
# load the log
@ -228,7 +228,7 @@ def main():
#run the tests, and gather timings
testSuite = TestSuite()
startTime = time.time()
testSuite.run(logdata) # run tests
testSuite.run(logdata, args.verbose) # run tests
endTime = time.time()
if args.profile:
print "Test suite run time: %.2f seconds" % (endTime-startTime)

View File

@ -9,7 +9,7 @@ class TestBalanceTwist(Test):
self.name = "Balance/Twist"
self.enable = False # TEMP
def run(self, logdata):
def run(self, logdata, verbose):
self.result = TestResult()
self.result.status = TestResult.StatusType.PASS

View File

@ -9,7 +9,7 @@ class TestBrownout(Test):
def __init__(self):
self.name = "Brownout"
def run(self, logdata):
def run(self, logdata, verbose):
self.result = TestResult()
self.result.status = TestResult.StatusType.PASS

View File

@ -1,6 +1,8 @@
from LogAnalyzer import Test,TestResult
import DataflashLog
import math
class TestCompass(Test):
'''test for compass offsets and throttle interference'''
@ -8,7 +10,7 @@ class TestCompass(Test):
def __init__(self):
self.name = "Compass"
def run(self, logdata):
def run(self, logdata, verbose):
self.result = TestResult()
self.result.status = TestResult.StatusType.PASS
@ -19,7 +21,6 @@ class TestCompass(Test):
compassOfsX = logdata.parameters["COMPASS_OFS_X"]
compassOfsY = logdata.parameters["COMPASS_OFS_Y"]
compassOfsZ = logdata.parameters["COMPASS_OFS_Z"]
#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)\n" % (compassOfsX,compassOfsY,compassOfsZ)
@ -28,26 +29,79 @@ class TestCompass(Test):
if "MAG" in logdata.channels:
errMsg = ""
if logdata.channels["MAG"]["OfsX"].max() > maxOffset:
errMsg = errMsg + "\nX: %.2f\n" % logdata.channels["MAG"]["OfsX"].max()
errMsg = errMsg + "\nX: %.2f" % logdata.channels["MAG"]["OfsX"].max()
err = True
if logdata.channels["MAG"]["OfsX"].min() < -maxOffset:
errMsg = errMsg + "\nX: %.2f\n" % logdata.channels["MAG"]["OfsX"].min()
errMsg = errMsg + "\nX: %.2f" % logdata.channels["MAG"]["OfsX"].min()
err = True
if logdata.channels["MAG"]["OfsY"].max() > maxOffset:
errMsg = errMsg + "\nY: %.2f\n" % logdata.channels["MAG"]["OfsY"].max()
errMsg = errMsg + "\nY: %.2f" % logdata.channels["MAG"]["OfsY"].max()
err = True
if logdata.channels["MAG"]["OfsY"].min() < -maxOffset:
errMsg = errMsg + "\nY: %.2f\n" % logdata.channels["MAG"]["OfsY"].min()
errMsg = errMsg + "\nY: %.2f" % logdata.channels["MAG"]["OfsY"].min()
err = True
if logdata.channels["MAG"]["OfsZ"].max() > maxOffset:
errMsg = errMsg + "\nZ: %.2f\n" % logdata.channels["MAG"]["OfsZ"].max()
errMsg = errMsg + "\nZ: %.2f" % logdata.channels["MAG"]["OfsZ"].max()
err = True
if logdata.channels["MAG"]["OfsZ"].min() < -maxOffset:
errMsg = errMsg + "\nZ: %.2f\n" % logdata.channels["MAG"]["OfsZ"].min()
errMsg = errMsg + "\nZ: %.2f" % logdata.channels["MAG"]["OfsZ"].min()
err = True
if errMsg:
self.result.status = TestResult.StatusType.FAIL
self.result.statusMessage = self.result.statusMessage + "Large compass offset in MAG data:" + errMsg
self.result.statusMessage = self.result.statusMessage + "Large compass offset in MAG data:" + errMsg + "\n"
# check for mag field length change, and length outside of recommended range
if "MAG" in logdata.channels:
percentDiffThresholdWARN = 0.25
percentDiffThresholdFAIL = 0.35
minMagFieldThreshold = 120.0
maxMagFieldThreshold = 550.0
index = 0
length = len(logdata.channels["MAG"]["MagX"].listData)
magField = []
(minMagField, maxMagField) = (None,None)
(minMagFieldLine, maxMagFieldLine) = (None,None)
while index<length:
mx = logdata.channels["MAG"]["MagX"].listData[index][1]
my = logdata.channels["MAG"]["MagY"].listData[index][1]
mz = logdata.channels["MAG"]["MagZ"].listData[index][1]
mf = math.sqrt(mx*mx + my*my + mz*mz)
magField.append(mf)
if mf<minMagField:
minMagField = mf
minMagFieldLine = logdata.channels["MAG"]["MagX"].listData[index][0]
if mf>maxMagField:
maxMagField = mf
maxMagFieldLine = logdata.channels["MAG"]["MagX"].listData[index][0]
if index == 0:
(minMagField, maxMagField) = (mf,mf)
index += 1
percentDiff = (maxMagField-minMagField) / minMagField
if percentDiff > percentDiffThresholdFAIL:
self.result.status = TestResult.StatusType.FAIL
self.result.statusMessage = self.result.statusMessage + "Large change in mag_field (%.2f%%)\n" % (percentDiff*100)
elif percentDiff > percentDiffThresholdWARN:
if self.result.status != TestResult.StatusType.FAIL:
self.result.status = TestResult.StatusType.WARN
self.result.statusMessage = self.result.statusMessage + "Moderate change in mag_field (%.2f%%)\n" % (percentDiff*100)
else:
self.result.statusMessage = self.result.statusMessage + "Good mag_field (%.2f%%)\n" % (percentDiff*100)
if minMagField < minMagFieldThreshold:
self.result.statusMessage = self.result.statusMessage + "Min mag field length (%.2f) < recommended (%.2f)\n" % (minMagField,minMagFieldThreshold)
if maxMagField > maxMagFieldThreshold:
self.result.statusMessage = self.result.statusMessage + "Max mag field length (%.2f) > recommended (%.2f)\n" % (maxMagField,maxMagFieldThreshold)
if verbose:
self.result.statusMessage = self.result.statusMessage + "Min mag_field of %.2f on line %d\n" % (minMagField,minMagFieldLine)
self.result.statusMessage = self.result.statusMessage + "Max mag_field of %.2f on line %d\n" % (maxMagField,maxMagFieldLine)
else:
self.result.statusMessage = self.result.statusMessage + "No MAG data, unable to test mag_field interference\n"
# 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%?

View File

@ -34,7 +34,7 @@ class TestDupeLogData(Test):
return False
def run(self, logdata):
def run(self, logdata, verbose):
self.result = TestResult()
self.result.status = TestResult.StatusType.PASS

View File

@ -8,7 +8,7 @@ class TestEmpty(Test):
def __init__(self):
self.name = "Empty"
def run(self, logdata):
def run(self, logdata, verbose):
self.result = TestResult()
self.result.status = TestResult.StatusType.PASS

View File

@ -8,7 +8,7 @@ class TestEvents(Test):
def __init__(self):
self.name = "Event/Failsafe"
def run(self, logdata):
def run(self, logdata, verbose):
self.result = TestResult()
self.result.status = TestResult.StatusType.PASS

View File

@ -8,7 +8,7 @@ class TestGPSGlitch(Test):
def __init__(self):
self.name = "GPS"
def run(self, logdata):
def run(self, logdata, verbose):
self.result = TestResult()
self.result.status = TestResult.StatusType.PASS

View File

@ -29,7 +29,7 @@ class TestParams(Test):
self.result.statusMessage = self.result.statusMessage + "%s set to %s, expecting less than %s\n" % (paramName, `value`, `minValue`)
def run(self, logdata):
def run(self, logdata, verbose):
self.result = TestResult()
self.result.status = TestResult.StatusType.PASS # PASS by default, tests below will override it if they fail

View File

@ -8,7 +8,7 @@ class TestPerformance(Test):
def __init__(self):
self.name = "PM"
def run(self, logdata):
def run(self, logdata, verbose):
self.result = TestResult()
self.result.status = TestResult.StatusType.PASS

View File

@ -10,7 +10,7 @@ class TestPitchRollCoupling(Test):
self.name = "Pitch/Roll"
self.enable = True # TEMP
def run(self, logdata):
def run(self, logdata, verbose):
self.result = TestResult()
self.result.status = TestResult.StatusType.PASS

View File

@ -8,7 +8,7 @@ class TestUnderpowered(Test):
def __init__(self):
self.name = "Underpowered"
def run(self, logdata):
def run(self, logdata, verbose):
self.result = TestResult()
self.result.status = TestResult.StatusType.PASS

View File

@ -10,7 +10,7 @@ class TestVCC(Test):
def __init__(self):
self.name = "VCC"
def run(self, logdata):
def run(self, logdata, verbose):
self.result = TestResult()
self.result.status = TestResult.StatusType.PASS

View File

@ -11,7 +11,7 @@ class TestVibration(Test):
self.name = "Vibration"
def run(self, logdata):
def run(self, logdata, verbose):
self.result = TestResult()
if logdata.vehicleType != "ArduCopter":