Tools: LogAnalyzer: TestGPSGlitch: flake8 compliance
This commit is contained in:
parent
7a077b5fa1
commit
a629bb7f2f
@ -1,5 +1,4 @@
|
||||
from LogAnalyzer import Test, TestResult
|
||||
import DataflashLog
|
||||
|
||||
|
||||
class TestGPSGlitch(Test):
|
||||
@ -28,10 +27,13 @@ class TestGPSGlitch(Test):
|
||||
self.result.statusMessage = "No GPS log data"
|
||||
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
|
||||
# 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))
|
||||
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]
|
||||
@ -39,10 +41,13 @@ class TestGPSGlitch(Test):
|
||||
gpsGlitchCount += 1
|
||||
if gpsGlitchCount:
|
||||
self.result.status = TestResult.StatusType.FAIL
|
||||
self.result.statusMessage = "GPS glitch errors found (%d)" % gpsGlitchCount
|
||||
self.result.statusMessage = ("GPS glitch errors found (%d)" %
|
||||
gpsGlitchCount)
|
||||
|
||||
# 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
|
||||
# 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
|
||||
minSatsFAIL = 5
|
||||
maxHDopWARN = 3.0
|
||||
@ -53,9 +58,11 @@ class TestGPSGlitch(Test):
|
||||
foundBadHDopWarn = hdopChan.max() > maxHDopWARN
|
||||
foundBadSatsFail = satsChan.min() < minSatsFAIL
|
||||
foundBadHDopFail = hdopChan.max() > maxHDopFAIL
|
||||
satsMsg = "Min satellites: %s, Max HDop: %s" % (satsChan.min(), hdopChan.max())
|
||||
satsMsg = ("Min satellites: %s, Max HDop: %s" %
|
||||
(satsChan.min(), hdopChan.max()))
|
||||
if gpsGlitchCount:
|
||||
self.result.statusMessage = self.result.statusMessage + "\n" + satsMsg
|
||||
self.result.statusMessage = "\n".join(self.result.statusMessage,
|
||||
satsMsg)
|
||||
if foundBadSatsFail or foundBadHDopFail:
|
||||
if not gpsGlitchCount:
|
||||
self.result.status = TestResult.StatusType.FAIL
|
||||
@ -64,5 +71,3 @@ class TestGPSGlitch(Test):
|
||||
if not gpsGlitchCount:
|
||||
self.result.status = TestResult.StatusType.WARN
|
||||
self.result.statusMessage = satsMsg
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user