mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Tools: loganalyzer: use new compass params
This commit is contained in:
parent
95713959ec
commit
b9c14b6cac
@ -30,9 +30,9 @@ class TestCompass(Test):
|
||||
warnOffset = 300
|
||||
failOffset = 500
|
||||
param_offsets = (
|
||||
logdata.parameters["COMPASS_OFS_X"],
|
||||
logdata.parameters["COMPASS_OFS_Y"],
|
||||
logdata.parameters["COMPASS_OFS_Z"]
|
||||
logdata.parameters["COMPASS1_OFS_X"],
|
||||
logdata.parameters["COMPASS1_OFS_Y"],
|
||||
logdata.parameters["COMPASS1_OFS_Z"]
|
||||
)
|
||||
|
||||
if vec_len(param_offsets) > failOffset:
|
||||
|
Loading…
Reference in New Issue
Block a user