mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Tools: changes from review feedback
This commit is contained in:
parent
dc58b0b950
commit
a96b6336b8
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user