mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
Preparation for conversion to parameter groups
This commit is contained in:
parent
6f872ba899
commit
79d4b2146d
90 changed files with 1150 additions and 507 deletions
|
@ -23,6 +23,9 @@
|
|||
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/barometer.h"
|
||||
#include "drivers/barometer_bmp085.h"
|
||||
#include "drivers/barometer_bmp280.h"
|
||||
|
@ -51,7 +54,9 @@ static int32_t baroGroundAltitude = 0;
|
|||
static int32_t baroGroundPressure = 0;
|
||||
static uint32_t baroPressureSum = 0;
|
||||
|
||||
#ifndef USE_PARAMETER_GROUPS
|
||||
static const barometerConfig_t *barometerConfig;
|
||||
#endif
|
||||
|
||||
bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
|
||||
{
|
||||
|
@ -121,7 +126,11 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
|
|||
|
||||
void useBarometerConfig(const barometerConfig_t *barometerConfigToUse)
|
||||
{
|
||||
#ifdef USE_PARAMETER_GROUPS
|
||||
(void)(barometerConfigToUse);
|
||||
#else
|
||||
barometerConfig = barometerConfigToUse;
|
||||
#endif
|
||||
}
|
||||
|
||||
bool isBaroCalibrationComplete(void)
|
||||
|
@ -160,7 +169,7 @@ static int32_t applyBarometerMedianFilter(int32_t newPressureReading)
|
|||
return newPressureReading;
|
||||
}
|
||||
|
||||
#define PRESSURE_SAMPLE_COUNT (barometerConfig->baro_sample_count - 1)
|
||||
#define PRESSURE_SAMPLE_COUNT (barometerConfig()->baro_sample_count - 1)
|
||||
|
||||
static uint32_t recalculateBarometerTotal(uint8_t baroSampleCount, uint32_t pressureTotal, int32_t newPressureReading)
|
||||
{
|
||||
|
@ -213,7 +222,7 @@ uint32_t baroUpdate(void)
|
|||
baro.dev.get_up();
|
||||
baro.dev.start_ut();
|
||||
baro.dev.calculate(&baroPressure, &baroTemperature);
|
||||
baroPressureSum = recalculateBarometerTotal(barometerConfig->baro_sample_count, baroPressureSum, baroPressure);
|
||||
baroPressureSum = recalculateBarometerTotal(barometerConfig()->baro_sample_count, baroPressureSum, baroPressure);
|
||||
state = BAROMETER_NEEDS_SAMPLES;
|
||||
return baro.dev.ut_delay;
|
||||
break;
|
||||
|
@ -228,7 +237,7 @@ int32_t baroCalculateAltitude(void)
|
|||
// 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
|
||||
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
|
||||
|
||||
return baro.BaroAlt;
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue