Browse Source

events: don't start baro calibration until specified temperature achieved

sbg
Paul Riseborough 8 years ago committed by Lorenz Meier
parent
commit
f3d30564ed
  1. 6
      src/modules/events/temperature_calibration/baro.cpp

6
src/modules/events/temperature_calibration/baro.cpp

@ -96,6 +96,12 @@ int TemperatureCalibrationBaro::update_sensor_instance(PerSensorData &data, int @@ -96,6 +96,12 @@ int TemperatureCalibrationBaro::update_sensor_instance(PerSensorData &data, int
data.sensor_sample_filt[0] = 100.0f * baro_data.pressure; // convert from hPA to Pa
data.sensor_sample_filt[1] = baro_data.temperature;
// wait for min start temp to be reached before starting calibration
if (data.sensor_sample_filt[1] < _min_start_temperature) {
return 1;
}
if (!data.cold_soaked) {
data.cold_soaked = true;
data.low_temp = data.sensor_sample_filt[1]; //Record the low temperature

Loading…
Cancel
Save