Tools: LogAnalyzer: correct Vcc test
This commit is contained in:
parent
b63666d188
commit
f1641161d7
@ -21,8 +21,17 @@ class TestVCC(Test):
|
||||
return
|
||||
|
||||
# just a naive min/max test for now
|
||||
vccMin = logdata.channels["CURR"]["Vcc"].min()
|
||||
vccMax = logdata.channels["CURR"]["Vcc"].max()
|
||||
try:
|
||||
vccMin = logdata.channels["CURR"]["Vcc"].min()
|
||||
vccMax = logdata.channels["CURR"]["Vcc"].max()
|
||||
except KeyError as e:
|
||||
# Vcc was renamed to Volts at some stage...
|
||||
vccMin = logdata.channels["CURR"]["Volt"].min()
|
||||
vccMax = logdata.channels["CURR"]["Volt"].max()
|
||||
# apparently it also changed to mV:
|
||||
vccMin *= 1000
|
||||
vccMax *= 1000
|
||||
|
||||
vccDiff = vccMax - vccMin;
|
||||
vccMinThreshold = 4.6 * 1000;
|
||||
vccMaxDiff = 0.3 * 1000;
|
||||
|
Loading…
Reference in New Issue
Block a user