mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
events: don't start gyro calibration until minimum temperature achieved
This commit is contained in:
parent
c901c4b39e
commit
cdf80a868a
@ -96,6 +96,11 @@ int TemperatureCalibrationGyro::update_sensor_instance(PerSensorData &data, int
|
||||
data.sensor_sample_filt[2] = gyro_data.z;
|
||||
data.sensor_sample_filt[3] = gyro_data.temperature;
|
||||
|
||||
// wait for min start temp to be reached before starting calibration
|
||||
if (data.sensor_sample_filt[3] < _min_start_temperature) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (!data.cold_soaked) {
|
||||
data.cold_soaked = true;
|
||||
data.low_temp = data.sensor_sample_filt[3]; //Record the low temperature
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user