Merge pull request #2429 from ellingo/master
Barometer initialization improvements
This commit is contained in:
commit
02bc606d22
|
@ -61,7 +61,7 @@ static int32_t baroPressure = 0;
|
|||
static int32_t baroTemperature = 0;
|
||||
|
||||
static int32_t baroGroundAltitude = 0;
|
||||
static int32_t baroGroundPressure = 0;
|
||||
static int32_t baroGroundPressure = 8*101325;
|
||||
static uint32_t baroPressureSum = 0;
|
||||
|
||||
bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
|
||||
|
@ -226,20 +226,31 @@ int32_t baroCalculateAltitude(void)
|
|||
|
||||
// calculates height from ground via baro readings
|
||||
// see: https://github.com/diydrones/ardupilot/blob/master/libraries/AP_Baro/AP_Baro.cpp#L140
|
||||
BaroAlt_tmp = lrintf((1.0f - powf((float)(baroPressureSum / PRESSURE_SAMPLE_COUNT) / 101325.0f, 0.190295f)) * 4433000.0f); // in cm
|
||||
BaroAlt_tmp -= baroGroundAltitude;
|
||||
baro.BaroAlt = lrintf((float)baro.BaroAlt * barometerConfig()->baro_noise_lpf + (float)BaroAlt_tmp * (1.0f - barometerConfig()->baro_noise_lpf)); // additional LPF to reduce baro noise
|
||||
|
||||
if (isBaroCalibrationComplete()) {
|
||||
BaroAlt_tmp = lrintf((1.0f - powf((float)(baroPressureSum / PRESSURE_SAMPLE_COUNT) / 101325.0f, 0.190295f)) * 4433000.0f); // in cm
|
||||
BaroAlt_tmp -= baroGroundAltitude;
|
||||
baro.BaroAlt = lrintf((float)baro.BaroAlt * barometerConfig()->baro_noise_lpf + (float)BaroAlt_tmp * (1.0f - barometerConfig()->baro_noise_lpf)); // additional LPF to reduce baro noise
|
||||
}
|
||||
else {
|
||||
baro.BaroAlt = 0;
|
||||
}
|
||||
return baro.BaroAlt;
|
||||
}
|
||||
|
||||
void performBaroCalibrationCycle(void)
|
||||
{
|
||||
static int32_t savedGroundPressure = 0;
|
||||
|
||||
baroGroundPressure -= baroGroundPressure / 8;
|
||||
baroGroundPressure += baroPressureSum / PRESSURE_SAMPLE_COUNT;
|
||||
baroGroundAltitude = (1.0f - powf((baroGroundPressure / 8) / 101325.0f, 0.190295f)) * 4433000.0f;
|
||||
|
||||
calibratingB--;
|
||||
if (baroGroundPressure == savedGroundPressure)
|
||||
calibratingB = 0;
|
||||
else {
|
||||
calibratingB--;
|
||||
savedGroundPressure=baroGroundPressure;
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* BARO */
|
||||
|
|
Loading…
Reference in New Issue