From ae677f37c5520dc1775f08572cb7e94afb656bd3 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Thu, 19 Dec 2024 17:52:22 +0100 Subject: [PATCH] IMPROVEMENT: Andy Piper fix to tempcal script --- ardupilot_methodic_configurator/tempcal_imu.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ardupilot_methodic_configurator/tempcal_imu.py b/ardupilot_methodic_configurator/tempcal_imu.py index 3573215f..ce3b33cc 100755 --- a/ardupilot_methodic_configurator/tempcal_imu.py +++ b/ardupilot_methodic_configurator/tempcal_imu.py @@ -119,7 +119,7 @@ def correction(self, coeff: dict, imu: int, temperature: float, axis: str, cal_t def correction_accel(self, imu: int, temperature: float) -> Vector3: """ - calculate accel correction from temperature calibration from + Calculate accel correction from temperature calibration from log data using parameters. """ cal_temp = self.atcal.get(imu, TEMP_REF) @@ -131,7 +131,7 @@ def correction_accel(self, imu: int, temperature: float) -> Vector3: def correction_gyro(self, imu: int, temperature: float) -> Vector3: """ - calculate gyro correction from temperature calibration from + Calculate gyro correction from temperature calibration from log data using parameters. """ cal_temp = self.gtcal.get(imu, TEMP_REF) @@ -366,7 +366,7 @@ def IMUfit( # noqa: PLR0915, N802, pylint: disable=too-many-locals, too-many-br stype = m.group(2) p = int(m.group(3)) axis = m.group(4) - if stop_capture[imu]: + if stop_capture[imu] or c.enable[imu] == 2: continue if stype == "ACC": c.set_acoeff(imu, axis, p, msg.Value / SCALE_FACTOR)