mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 20:10:18 +03:00
Merge pull request #10481 from mikeller/fix_baro_sample_count_setting
Fixed incorrect parameter value for barometer sample count.
This commit is contained in:
commit
f77b6a59c3
2 changed files with 9 additions and 11 deletions
|
@ -726,7 +726,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "baro_i2c_device", VAR_UINT8 | HARDWARE_VALUE, .config.minmaxUnsigned = { 0, 5 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_i2c_device) },
|
||||
{ "baro_i2c_address", VAR_UINT8 | HARDWARE_VALUE, .config.minmaxUnsigned = { 0, I2C_ADDR7_MAX }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_i2c_address) },
|
||||
{ "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BARO_HARDWARE }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_hardware) },
|
||||
{ "baro_tab_size", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 2, BARO_SAMPLE_COUNT_MAX }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_sample_count) },
|
||||
{ "baro_tab_size", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 1, BARO_SAMPLE_COUNT_MAX }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_sample_count) },
|
||||
{ "baro_noise_lpf", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 1000 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_noise_lpf) },
|
||||
{ "baro_cf_vel", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 1000 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_cf_vel) },
|
||||
#endif
|
||||
|
|
|
@ -338,24 +338,22 @@ static int32_t applyBarometerMedianFilter(int32_t newPressureReading)
|
|||
return newPressureReading;
|
||||
}
|
||||
|
||||
#define PRESSURE_SAMPLE_COUNT (barometerConfig()->baro_sample_count - 1)
|
||||
|
||||
static uint32_t recalculateBarometerTotal(uint8_t baroSampleCount, uint32_t pressureTotal, int32_t newPressureReading)
|
||||
static uint32_t recalculateBarometerTotal(uint32_t pressureTotal, int32_t newPressureReading)
|
||||
{
|
||||
static int32_t barometerSamples[BARO_SAMPLE_COUNT_MAX];
|
||||
static int32_t barometerSamples[BARO_SAMPLE_COUNT_MAX + 1];
|
||||
static int currentSampleIndex = 0;
|
||||
int nextSampleIndex;
|
||||
|
||||
// store current pressure in barometerSamples
|
||||
nextSampleIndex = (currentSampleIndex + 1);
|
||||
if (nextSampleIndex == baroSampleCount) {
|
||||
if (currentSampleIndex >= barometerConfig()->baro_sample_count) {
|
||||
nextSampleIndex = 0;
|
||||
baroReady = true;
|
||||
} else {
|
||||
nextSampleIndex = (currentSampleIndex + 1);
|
||||
}
|
||||
barometerSamples[currentSampleIndex] = applyBarometerMedianFilter(newPressureReading);
|
||||
|
||||
// recalculate pressure total
|
||||
// Note, the pressure total is made up of baroSampleCount - 1 samples - See PRESSURE_SAMPLE_COUNT
|
||||
pressureTotal += barometerSamples[currentSampleIndex];
|
||||
pressureTotal -= barometerSamples[nextSampleIndex];
|
||||
|
||||
|
@ -427,7 +425,7 @@ uint32_t baroUpdate(void)
|
|||
baro.dev.calculate(&baroPressure, &baroTemperature);
|
||||
baro.baroPressure = baroPressure;
|
||||
baro.baroTemperature = baroTemperature;
|
||||
baroPressureSum = recalculateBarometerTotal(barometerConfig()->baro_sample_count, baroPressureSum, baroPressure);
|
||||
baroPressureSum = recalculateBarometerTotal(baroPressureSum, baroPressure);
|
||||
if (baro.dev.combined_read) {
|
||||
state = BAROMETER_NEEDS_PRESSURE_START;
|
||||
} else {
|
||||
|
@ -458,7 +456,7 @@ int32_t baroCalculateAltitude(void)
|
|||
|
||||
// calculates height from ground via baro readings
|
||||
if (baroIsCalibrationComplete()) {
|
||||
BaroAlt_tmp = lrintf(pressureToAltitude((float)(baroPressureSum / PRESSURE_SAMPLE_COUNT)));
|
||||
BaroAlt_tmp = lrintf(pressureToAltitude((float)(baroPressureSum / barometerConfig()->baro_sample_count)));
|
||||
BaroAlt_tmp -= baroGroundAltitude;
|
||||
baro.BaroAlt = lrintf((float)baro.BaroAlt * CONVERT_PARAMETER_TO_FLOAT(barometerConfig()->baro_noise_lpf) + (float)BaroAlt_tmp * (1.0f - CONVERT_PARAMETER_TO_FLOAT(barometerConfig()->baro_noise_lpf))); // additional LPF to reduce baro noise
|
||||
}
|
||||
|
@ -473,7 +471,7 @@ void performBaroCalibrationCycle(void)
|
|||
static int32_t savedGroundPressure = 0;
|
||||
|
||||
baroGroundPressure -= baroGroundPressure / 8;
|
||||
baroGroundPressure += baroPressureSum / PRESSURE_SAMPLE_COUNT;
|
||||
baroGroundPressure += baroPressureSum / barometerConfig()->baro_sample_count;
|
||||
baroGroundAltitude = (1.0f - pow_approx((baroGroundPressure / 8) / 101325.0f, 0.190259f)) * 4433000.0f;
|
||||
|
||||
if (baroGroundPressure == savedGroundPressure) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue