From a96b6336b8f616f1aeaa27b3246e40043895d387 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 17 Jan 2021 09:26:22 +1100 Subject: [PATCH] Tools: changes from review feedback --- Tools/scripts/tempcal_IMU.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Tools/scripts/tempcal_IMU.py b/Tools/scripts/tempcal_IMU.py index f931cc1af9..ecae916cfd 100755 --- a/Tools/scripts/tempcal_IMU.py +++ b/Tools/scripts/tempcal_IMU.py @@ -297,13 +297,13 @@ def IMUfit(logfile): if stop_capture[imu]: continue c.set_tmax(imu, msg.Value) - m = re.match("^INS_GYR_CALTEMP(\d)", msg.Name) + m = re.match("^INS_GYR(\d)_CALTEMP", msg.Name) if m: imu = int(m.group(1))-1 if stop_capture[imu]: continue c.set_gyro_tcal(imu, msg.Value) - m = re.match("^INS_ACC_CALTEMP(\d)", msg.Name) + m = re.match("^INS_ACC(\d)_CALTEMP", msg.Name) if m: imu = int(m.group(1))-1 if stop_capture[imu]: @@ -317,12 +317,12 @@ def IMUfit(logfile): imu = msg.I T = msg.Temp - if msg.Si == 0: + if msg.SType == 0: # accel acc = Vector3(msg.X, msg.Y, msg.Z) time = msg.TimeUS*1.0e-6 data.add_accel(imu, T, time, acc) - elif msg.Si == 1: + elif msg.SType == 1: # gyro gyr = Vector3(msg.X, msg.Y, msg.Z) time = msg.TimeUS*1.0e-6