2014-01-27 02:38:57 -04:00
|
|
|
from LogAnalyzer import Test,TestResult
|
|
|
|
import DataflashLog
|
|
|
|
|
|
|
|
|
|
|
|
class TestGPSGlitch(Test):
|
2014-02-26 08:50:55 -04:00
|
|
|
'''test for GPS glitch reporting or bad GPS data (satellite count, hdop)'''
|
2014-01-27 02:38:57 -04:00
|
|
|
|
|
|
|
def __init__(self):
|
2014-06-27 20:11:23 -03:00
|
|
|
Test.__init__(self)
|
2014-01-27 02:38:57 -04:00
|
|
|
self.name = "GPS"
|
|
|
|
|
2014-03-03 13:46:17 -04:00
|
|
|
def run(self, logdata, verbose):
|
2014-01-27 02:38:57 -04:00
|
|
|
self.result = TestResult()
|
2014-06-15 18:35:14 -03:00
|
|
|
self.result.status = TestResult.StatusType.GOOD
|
2014-01-30 05:33:25 -04:00
|
|
|
|
|
|
|
if "GPS" not in logdata.channels:
|
2014-02-22 15:36:30 -04:00
|
|
|
self.result.status = TestResult.StatusType.UNKNOWN
|
2014-01-30 05:33:25 -04:00
|
|
|
self.result.statusMessage = "No GPS log data"
|
|
|
|
return
|
|
|
|
|
2014-02-26 08:50:55 -04:00
|
|
|
# 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
|
|
|
|
|
2014-01-27 02:38:57 -04:00
|
|
|
# define and check different thresholds for WARN level and FAIL level
|
2014-02-26 08:50:55 -04:00
|
|
|
# TODO: for plane, only check after first instance of throttle > 0, or after takeoff if we can reliably detect it
|
2014-01-27 02:38:57 -04:00
|
|
|
minSatsWARN = 6
|
|
|
|
minSatsFAIL = 5
|
|
|
|
maxHDopWARN = 3.0
|
|
|
|
maxHDopFAIL = 10.0
|
|
|
|
foundBadSatsWarn = logdata.channels["GPS"]["NSats"].min() < minSatsWARN
|
|
|
|
foundBadHDopWarn = logdata.channels["GPS"]["HDop"].max() > maxHDopWARN
|
|
|
|
foundBadSatsFail = logdata.channels["GPS"]["NSats"].min() < minSatsFAIL
|
|
|
|
foundBadHDopFail = logdata.channels["GPS"]["HDop"].max() > maxHDopFAIL
|
2014-02-26 08:50:55 -04:00
|
|
|
satsMsg = "Min satellites: %s, Max HDop: %s" % (logdata.channels["GPS"]["NSats"].min(), logdata.channels["GPS"]["HDop"].max())
|
|
|
|
if gpsGlitchCount:
|
2014-02-26 15:22:22 -04:00
|
|
|
self.result.statusMessage = self.result.statusMessage + "\n" + satsMsg
|
2014-01-27 02:38:57 -04:00
|
|
|
if foundBadSatsFail or foundBadHDopFail:
|
2014-02-26 08:50:55 -04:00
|
|
|
if not gpsGlitchCount:
|
|
|
|
self.result.status = TestResult.StatusType.FAIL
|
|
|
|
self.result.statusMessage = satsMsg
|
2014-01-27 02:38:57 -04:00
|
|
|
elif foundBadSatsWarn or foundBadHDopWarn:
|
2014-02-26 08:50:55 -04:00
|
|
|
if not gpsGlitchCount:
|
|
|
|
self.result.status = TestResult.StatusType.WARN
|
|
|
|
self.result.statusMessage = satsMsg
|
2014-03-03 14:55:25 -04:00
|
|
|
|
|
|
|
|