Tools: autotest: fix FixedYawCalibration
This commit is contained in:
parent
2c3bd61eb4
commit
a5e9da337a
@ -4725,6 +4725,14 @@ class AutoTest(ABC):
|
||||
self.set_parameter("SIM_MAG_OFS_X", MAG_OFS_X)
|
||||
self.set_parameter("SIM_MAG_OFS_Y", MAG_OFS_Y)
|
||||
self.set_parameter("SIM_MAG_OFS_Z", MAG_OFS_Z)
|
||||
|
||||
self.set_parameter("SIM_MAG2_OFS_X", MAG_OFS_X)
|
||||
self.set_parameter("SIM_MAG2_OFS_Y", MAG_OFS_Y)
|
||||
self.set_parameter("SIM_MAG2_OFS_Z", MAG_OFS_Z)
|
||||
|
||||
self.set_parameter("SIM_MAG3_OFS_X", MAG_OFS_X)
|
||||
self.set_parameter("SIM_MAG3_OFS_Y", MAG_OFS_Y)
|
||||
self.set_parameter("SIM_MAG3_OFS_Z", MAG_OFS_Z)
|
||||
# set to some sensible-ish initial values. If your initial
|
||||
# offsets are way, way off you can get some very odd effects.
|
||||
for param in wanted:
|
||||
|
Loading…
Reference in New Issue
Block a user