mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 08:23:56 -04:00
LogAnalyzer: added GPS glitch detection to GPS test
This commit is contained in:
parent
90f07aae61
commit
2a406ac699
@ -8,6 +8,7 @@ import pprint # temp
|
|||||||
import collections
|
import collections
|
||||||
import os
|
import os
|
||||||
import numpy
|
import numpy
|
||||||
|
import bisect
|
||||||
|
|
||||||
|
|
||||||
class Format:
|
class Format:
|
||||||
@ -50,6 +51,7 @@ class Channel:
|
|||||||
def avg(self):
|
def avg(self):
|
||||||
return numpy.mean(self.dictData.values())
|
return numpy.mean(self.dictData.values())
|
||||||
def getNearestValue(self, lineNumber, lookForwards=True):
|
def getNearestValue(self, lineNumber, lookForwards=True):
|
||||||
|
# TODO: redo Channel.getNearestValue() using listData and bisect, profile speed of TestUnderpowered before/after
|
||||||
'''find the nearest data value to the given lineNumber, defaults to looking forwards. Returns (value,lineNumber)'''
|
'''find the nearest data value to the given lineNumber, defaults to looking forwards. Returns (value,lineNumber)'''
|
||||||
if lineNumber in self.dictData:
|
if lineNumber in self.dictData:
|
||||||
return (self.dictData[lineNumber], lineNumber)
|
return (self.dictData[lineNumber], lineNumber)
|
||||||
@ -72,6 +74,11 @@ class Channel:
|
|||||||
return prevValue
|
return prevValue
|
||||||
weight = (lineNumber-prevValueLine) / float(nextValueLine-prevValueLine)
|
weight = (lineNumber-prevValueLine) / float(nextValueLine-prevValueLine)
|
||||||
return ((weight*prevValue) + ((1-weight)*nextValue))
|
return ((weight*prevValue) + ((1-weight)*nextValue))
|
||||||
|
def getIndexOf(self, lineNumber):
|
||||||
|
index = bisect.bisect_left(self.listData, (lineNumber,0)) - 1
|
||||||
|
print "INDEX: %d" % index
|
||||||
|
assert(self.listData[index][0] == lineNumber)
|
||||||
|
return index
|
||||||
|
|
||||||
# class LogIterator:
|
# 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'''
|
# '''Smart iterator that can move through a log by line number and maintain an index into the nearest values of all data channels'''
|
||||||
@ -217,8 +224,8 @@ class DataflashLog:
|
|||||||
def read(self, logfile, ignoreBadlines=False):
|
def read(self, logfile, ignoreBadlines=False):
|
||||||
'''returns True on successful log read (including bad lines if ignoreBadlines==True), False otherwise'''
|
'''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: 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
|
# 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
|
self.filename = logfile
|
||||||
f = open(self.filename, 'r')
|
f = open(self.filename, 'r')
|
||||||
lineNumber = 0
|
lineNumber = 0
|
||||||
@ -311,6 +318,7 @@ class DataflashLog:
|
|||||||
# gather some general stats about the log
|
# gather some general stats about the log
|
||||||
self.lineCount = lineNumber
|
self.lineCount = lineNumber
|
||||||
self.filesizeKB = os.path.getsize(self.filename) / 1024.0
|
self.filesizeKB = os.path.getsize(self.filename) / 1024.0
|
||||||
|
# TODO: switch duration calculation to use TimeMS values rather than GPS timestemp
|
||||||
if "GPS" in self.channels:
|
if "GPS" in self.channels:
|
||||||
# the GPS time label changed at some point, need to handle both
|
# the GPS time label changed at some point, need to handle both
|
||||||
timeLabel = "TimeMS"
|
timeLabel = "TimeMS"
|
||||||
|
@ -118,7 +118,7 @@ class TestSuite:
|
|||||||
print " %20s: UNKNOWN %-50s%s" % (test.name, test.result.statusMessage,execTime)
|
print " %20s: UNKNOWN %-50s%s" % (test.name, test.result.statusMessage,execTime)
|
||||||
if test.result.extraFeedback:
|
if test.result.extraFeedback:
|
||||||
for line in test.result.extraFeedback.strip().split('\n'):
|
for line in test.result.extraFeedback.strip().split('\n'):
|
||||||
print " %20s %s" % ("",line)
|
print " %29s %s" % ("",line)
|
||||||
|
|
||||||
print '\n'
|
print '\n'
|
||||||
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 'The Log Analyzer is currently BETA code.\nFor any support or feedback on the log analyzer please email Andrew Chapman (amchapman@gmail.com)'
|
||||||
|
@ -7,12 +7,13 @@ class TestBalanceTwist(Test):
|
|||||||
|
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
self.name = "Balance/Twist"
|
self.name = "Balance/Twist"
|
||||||
|
self.enable = False # TEMP
|
||||||
|
|
||||||
def run(self, logdata):
|
def run(self, logdata):
|
||||||
self.result = TestResult()
|
self.result = TestResult()
|
||||||
self.result.status = TestResult.StatusType.PASS
|
self.result.status = TestResult.StatusType.PASS
|
||||||
|
|
||||||
if logdata.vehicleType == "ArduPlane":
|
if logdata.vehicleType != "ArduCopter":
|
||||||
self.result.status = TestResult.StatusType.NA
|
self.result.status = TestResult.StatusType.NA
|
||||||
|
|
||||||
# TODO: implement copter test for unbalanced or twisted copter frame
|
# TODO: implement copter test for unbalanced or twisted copter frame
|
@ -3,7 +3,7 @@ import DataflashLog
|
|||||||
|
|
||||||
|
|
||||||
class TestGPSGlitch(Test):
|
class TestGPSGlitch(Test):
|
||||||
'''test for bad GPS data (satellite count, hdop), and later for sudden repositioning beyond what the drone could do'''
|
'''test for GPS glitch reporting or bad GPS data (satellite count, hdop)'''
|
||||||
|
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
self.name = "GPS"
|
self.name = "GPS"
|
||||||
@ -17,7 +17,21 @@ class TestGPSGlitch(Test):
|
|||||||
self.result.statusMessage = "No GPS log data"
|
self.result.statusMessage = "No GPS log data"
|
||||||
return
|
return
|
||||||
|
|
||||||
|
# glitch protection is currently copter-only, but might be added to other vehicle types later and there's no harm in leaving the test in for all
|
||||||
|
gpsGlitchCount = 0
|
||||||
|
if "ERR" in logdata.channels:
|
||||||
|
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 == 11 and (eCode == 2):
|
||||||
|
gpsGlitchCount += 1
|
||||||
|
if gpsGlitchCount:
|
||||||
|
self.result.status = TestResult.StatusType.FAIL
|
||||||
|
self.result.statusMessage = "GPS glitch errors found (%d)" % gpsGlitchCount
|
||||||
|
|
||||||
# define and check different thresholds for WARN level and FAIL level
|
# define and check different thresholds for WARN level and FAIL level
|
||||||
|
# TODO: for plane, only check after first instance of throttle > 0, or after takeoff if we can reliably detect it
|
||||||
minSatsWARN = 6
|
minSatsWARN = 6
|
||||||
minSatsFAIL = 5
|
minSatsFAIL = 5
|
||||||
maxHDopWARN = 3.0
|
maxHDopWARN = 3.0
|
||||||
@ -26,12 +40,14 @@ class TestGPSGlitch(Test):
|
|||||||
foundBadHDopWarn = logdata.channels["GPS"]["HDop"].max() > maxHDopWARN
|
foundBadHDopWarn = logdata.channels["GPS"]["HDop"].max() > maxHDopWARN
|
||||||
foundBadSatsFail = logdata.channels["GPS"]["NSats"].min() < minSatsFAIL
|
foundBadSatsFail = logdata.channels["GPS"]["NSats"].min() < minSatsFAIL
|
||||||
foundBadHDopFail = logdata.channels["GPS"]["HDop"].max() > maxHDopFAIL
|
foundBadHDopFail = logdata.channels["GPS"]["HDop"].max() > maxHDopFAIL
|
||||||
|
satsMsg = "Min satellites: %s, Max HDop: %s" % (logdata.channels["GPS"]["NSats"].min(), logdata.channels["GPS"]["HDop"].max())
|
||||||
|
if gpsGlitchCount:
|
||||||
|
self.result.extraFeedback = satsMsg
|
||||||
if foundBadSatsFail or foundBadHDopFail:
|
if foundBadSatsFail or foundBadHDopFail:
|
||||||
|
if not gpsGlitchCount:
|
||||||
self.result.status = TestResult.StatusType.FAIL
|
self.result.status = TestResult.StatusType.FAIL
|
||||||
self.result.statusMessage = "Min satellites: %s, Max HDop: %s" % (logdata.channels["GPS"]["NSats"].min(), logdata.channels["GPS"]["HDop"].max())
|
self.result.statusMessage = satsMsg
|
||||||
elif foundBadSatsWarn or foundBadHDopWarn:
|
elif foundBadSatsWarn or foundBadHDopWarn:
|
||||||
|
if not gpsGlitchCount:
|
||||||
self.result.status = TestResult.StatusType.WARN
|
self.result.status = TestResult.StatusType.WARN
|
||||||
self.result.statusMessage = "Min satellites: %s, Max HDop: %s" % (logdata.channels["GPS"]["NSats"].min(), logdata.channels["GPS"]["HDop"].max())
|
self.result.statusMessage = satsMsg
|
||||||
|
|
||||||
# TODO: also test for sudden repositioning beyond what the drone could reasonably achieve, like is done with glitch protection - or is that logged when it happens?
|
|
||||||
# ...
|
|
||||||
|
@ -50,6 +50,9 @@ class TestParams(Test):
|
|||||||
elif logdata.vehicleType == "ArduPlane":
|
elif logdata.vehicleType == "ArduPlane":
|
||||||
# TODO: add parameter checks for plane...
|
# TODO: add parameter checks for plane...
|
||||||
pass
|
pass
|
||||||
|
elif logdata.vehicleType == "ArduRover":
|
||||||
|
# TODO: add parameter checks for rover...
|
||||||
|
pass
|
||||||
|
|
||||||
if self.result.status == TestResult.StatusType.FAIL:
|
if self.result.status == TestResult.StatusType.FAIL:
|
||||||
self.result.statusMessage = "Bad parameters found:"
|
self.result.statusMessage = "Bad parameters found:"
|
||||||
|
@ -12,6 +12,7 @@ class TestPerformance(Test):
|
|||||||
self.result = TestResult()
|
self.result = TestResult()
|
||||||
self.result.status = TestResult.StatusType.PASS
|
self.result.status = TestResult.StatusType.PASS
|
||||||
|
|
||||||
|
# this test should be valid for all vehicle types, just need to figure out why PM logging data is different in each
|
||||||
if logdata.vehicleType != "ArduCopter":
|
if logdata.vehicleType != "ArduCopter":
|
||||||
self.result.status = TestResult.StatusType.NA
|
self.result.status = TestResult.StatusType.NA
|
||||||
return
|
return
|
||||||
|
@ -13,6 +13,14 @@ class TestPitchRollCoupling(Test):
|
|||||||
self.result = TestResult()
|
self.result = TestResult()
|
||||||
self.result.status = TestResult.StatusType.PASS
|
self.result.status = TestResult.StatusType.PASS
|
||||||
|
|
||||||
|
if logdata.vehicleType != "ArduCopter":
|
||||||
|
self.result.status = TestResult.StatusType.NA
|
||||||
|
|
||||||
|
if not "ATT" in logdata.channels:
|
||||||
|
self.result.status = TestResult.StatusType.UNKNOWN
|
||||||
|
self.result.statusMessage = "No ATT log data"
|
||||||
|
return
|
||||||
|
|
||||||
# TODO: implement pitch/roll input/output divergence testing -
|
# TODO: implement pitch/roll input/output divergence testing -
|
||||||
|
|
||||||
# note: names changed from PitchIn to DesPitch at some point, check for both
|
# note: names changed from PitchIn to DesPitch at some point, check for both
|
||||||
@ -27,10 +35,9 @@ class TestPitchRollCoupling(Test):
|
|||||||
|
|
||||||
|
|
||||||
# figure out where each mode begins and ends, so we can treat auto and manual modes differently
|
# figure out where each mode begins and ends, so we can treat auto and manual modes differently
|
||||||
# TODO: fill in all known modes here
|
autoModes = ["RTL","AUTO","LAND","LOITER","GUIDED","CIRCLE","OF_LOITER"] # use NTUN DRol+DPit
|
||||||
autoModes = ["RTL","AUTO","LAND","LOITER"] # use NTUN DRol+DPit
|
|
||||||
manualModes = ["STABILIZE","DRIFT","ALT_HOLD"] # use CTUN RollIn/DesRoll + PitchIn/DesPitch
|
manualModes = ["STABILIZE","DRIFT","ALT_HOLD"] # use CTUN RollIn/DesRoll + PitchIn/DesPitch
|
||||||
acroModes = ["ACRO","SPORT"] # ignore data from acro modes
|
ignoreModes = ["ACRO","SPORT","FLIP","AUTOTUNE"] # ignore data from these modes
|
||||||
autoSegments = [] # list of (startLine,endLine) pairs
|
autoSegments = [] # list of (startLine,endLine) pairs
|
||||||
manualSegments = [] # list of (startLine,endLine) pairs
|
manualSegments = [] # list of (startLine,endLine) pairs
|
||||||
orderedModes = collections.OrderedDict(sorted(logdata.modeChanges.items(), key=lambda t: t[0]))
|
orderedModes = collections.OrderedDict(sorted(logdata.modeChanges.items(), key=lambda t: t[0]))
|
||||||
@ -39,25 +46,45 @@ class TestPitchRollCoupling(Test):
|
|||||||
for line,modepair in orderedModes.iteritems():
|
for line,modepair in orderedModes.iteritems():
|
||||||
mode = modepair[0].upper()
|
mode = modepair[0].upper()
|
||||||
if mode in autoModes:
|
if mode in autoModes:
|
||||||
print "On line %d mode changed to %s (AUTO)" % (line,mode)
|
print "On line %d mode changed to %s (AUTO)" % (line,mode) # TEMP
|
||||||
if not isAuto:
|
if not isAuto:
|
||||||
manualSegments.append((prevLine,line-1))
|
manualSegments.append((prevLine,line-1))
|
||||||
print " Previous manual segment: " + `(prevLine,line-1)`
|
print " Previous manual segment: " + `(prevLine,line-1)` # TEMP
|
||||||
|
prevLine = line
|
||||||
isAuto = True
|
isAuto = True
|
||||||
elif mode in manualModes:
|
elif mode in manualModes:
|
||||||
print "On line %d mode changed to %s (MANUAL)" % (line,mode)
|
print "On line %d mode changed to %s (MANUAL)" % (line,mode) # TEMP
|
||||||
if isAuto:
|
if isAuto:
|
||||||
autoSegments.append((prevLine,line-1))
|
autoSegments.append((prevLine,line-1))
|
||||||
print " Previous auto segment: " + `(prevLine,line-1)`
|
print " Previous auto segment: " + `(prevLine,line-1)` # TEMP
|
||||||
|
prevLine = line
|
||||||
isAuto = False
|
isAuto = False
|
||||||
elif mode in acroModes:
|
elif mode in ignoreModes:
|
||||||
pass
|
pass
|
||||||
else:
|
else:
|
||||||
raise Exception("Unknown mode: %s" % mode)
|
raise Exception("Unknown mode in TestPitchRollCoupling: %s" % mode)
|
||||||
prevLine = line
|
|
||||||
if isAuto:
|
# look through manual segments
|
||||||
autoSegments.append((prevLine,logdata.lineCount))
|
for startLine,endLine in manualSegments:
|
||||||
print " Previous auto segment: " + `(prevLine,logdata.lineCount)`
|
(value,attLine) = logdata.channels["ATT"]["Roll"].getNearestValue(startLine, lookForwards=True)
|
||||||
else:
|
print "Nearest ATT line after %d is %d" % (startLine,attLine)
|
||||||
manualSegments.append((prevLine,logdata.lineCount))
|
index = logdata.channels["ATT"]["Roll"].getIndexOf(attLine)
|
||||||
print " Previous manual segment: " + `(prevLine,logdata.lineCount)`
|
print "First ATT line in manual segment (%d,%d) is line %d" % (startLine,endLine,logdata.channels["ATT"]["Roll"].listData[index][0])
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
# look through auto segments
|
||||||
|
# ...
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -14,6 +14,10 @@ class TestVibration(Test):
|
|||||||
def run(self, logdata):
|
def run(self, logdata):
|
||||||
self.result = TestResult()
|
self.result = TestResult()
|
||||||
|
|
||||||
|
if logdata.vehicleType != "ArduCopter":
|
||||||
|
self.result.status = TestResult.StatusType.NA
|
||||||
|
return
|
||||||
|
|
||||||
# constants
|
# constants
|
||||||
gravity = -9.81
|
gravity = -9.81
|
||||||
aimRangeWarnXY = 1.5
|
aimRangeWarnXY = 1.5
|
||||||
|
Loading…
Reference in New Issue
Block a user