1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-11-30 08:24:11 +01:00

do not calibrate if there is a pre-stored calibration value

This commit is contained in:
Corvus Corax 2012-11-05 10:41:24 +01:00
parent 774dde3da5
commit 5bf18780c1

View File

@ -77,7 +77,9 @@ void baro_airspeedGetETASV3(BaroAirspeedData *baroAirspeedData, portTickType *la
return;
}
//Calibrate sensor by averaging zero point value //THIS SHOULD NOT BE DONE IF THERE IS AN IN-AIR RESET. HOW TO DETECT THIS?
// only calibrate if no stored calibration is available
if (!airspeedSettingsData.ZeroPoint) {
//Calibrate sensor by averaging zero point value
if (calibrationCount < CALIBRATION_IDLE_MS/SAMPLING_DELAY_MS_ETASV3) {
calibrationCount++;
return;
@ -92,6 +94,7 @@ void baro_airspeedGetETASV3(BaroAirspeedData *baroAirspeedData, portTickType *la
return;
}
}
}
//Compute airspeed
float calibratedAirspeed = ETS_AIRSPEED_SCALE * sqrtf((float)abs(baroAirspeedData->SensorValue - airspeedSettingsData.ZeroPoint)); //Is this calibrated or indicated airspeed?