Tools: fixed stopping of capture on enable change in tempcal

This commit is contained in:
Andrew Tridgell 2021-01-18 12:30:24 +11:00 committed by Peter Barker
parent 285b53fe07
commit 2359a5a1ea

View File

@ -104,8 +104,7 @@ class Coefficients:
temperature = constrain(temperature, self.tmin[imu], self.tmax[imu])
cal_temp = constrain(cal_temp, self.tmin[imu], self.tmax[imu])
poly = np.poly1d(coeff[axis])
ret = poly(cal_temp - TEMP_REF) - poly(temperature - TEMP_REF)
return ret
return poly(cal_temp - TEMP_REF) - poly(temperature - TEMP_REF)
def correction_accel(self, imu, temperature):
'''calculate accel correction from temperature calibration from
@ -336,6 +335,9 @@ def IMUfit(logfile):
if msg.get_type() == 'IMU' and not args.tclr:
imu = msg.I
if stop_capture[imu]:
continue
T = msg.T
acc = Vector3(msg.AccX, msg.AccY, msg.AccZ)
gyr = Vector3(msg.GyrX, msg.GyrY, msg.GyrZ)