Skip to content

Commit

Permalink
IMPROVEMENT: Andy Piper fix to tempcal script
Browse files Browse the repository at this point in the history
  • Loading branch information
amilcarlucas committed Dec 19, 2024
1 parent 990cd1e commit ae677f3
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions ardupilot_methodic_configurator/tempcal_imu.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -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)
Expand Down Expand Up @@ -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)
Expand Down

0 comments on commit ae677f3

Please sign in to comment.