mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Tools: fixed stopping of capture on enable change in tempcal
This commit is contained in:
parent
285b53fe07
commit
2359a5a1ea
@ -104,8 +104,7 @@ class Coefficients:
|
|||||||
temperature = constrain(temperature, self.tmin[imu], self.tmax[imu])
|
temperature = constrain(temperature, self.tmin[imu], self.tmax[imu])
|
||||||
cal_temp = constrain(cal_temp, self.tmin[imu], self.tmax[imu])
|
cal_temp = constrain(cal_temp, self.tmin[imu], self.tmax[imu])
|
||||||
poly = np.poly1d(coeff[axis])
|
poly = np.poly1d(coeff[axis])
|
||||||
ret = poly(cal_temp - TEMP_REF) - poly(temperature - TEMP_REF)
|
return poly(cal_temp - TEMP_REF) - poly(temperature - TEMP_REF)
|
||||||
return ret
|
|
||||||
|
|
||||||
def correction_accel(self, imu, temperature):
|
def correction_accel(self, imu, temperature):
|
||||||
'''calculate accel correction from temperature calibration from
|
'''calculate accel correction from temperature calibration from
|
||||||
@ -336,6 +335,9 @@ def IMUfit(logfile):
|
|||||||
if msg.get_type() == 'IMU' and not args.tclr:
|
if msg.get_type() == 'IMU' and not args.tclr:
|
||||||
imu = msg.I
|
imu = msg.I
|
||||||
|
|
||||||
|
if stop_capture[imu]:
|
||||||
|
continue
|
||||||
|
|
||||||
T = msg.T
|
T = msg.T
|
||||||
acc = Vector3(msg.AccX, msg.AccY, msg.AccZ)
|
acc = Vector3(msg.AccX, msg.AccY, msg.AccZ)
|
||||||
gyr = Vector3(msg.GyrX, msg.GyrY, msg.GyrZ)
|
gyr = Vector3(msg.GyrX, msg.GyrY, msg.GyrZ)
|
||||||
|
Loading…
Reference in New Issue
Block a user