1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-14 20:10:18 +03:00

Improve ACC filter initialisation

This commit is contained in:
Martin Budden 2017-11-24 07:23:19 +00:00
parent f26d461dd6
commit ed04a1f24a
4 changed files with 5 additions and 5 deletions

View file

@ -307,7 +307,7 @@ void activateConfig(void)
failsafeReset(); failsafeReset();
setAccelerationTrims(&accelerometerConfigMutable()->accZero); setAccelerationTrims(&accelerometerConfigMutable()->accZero);
setAccelerationFilter(accelerometerConfig()->acc_lpf_hz); accInitFilters();
imuConfigure(throttleCorrectionConfig()->throttle_correction_angle); imuConfigure(throttleCorrectionConfig()->throttle_correction_angle);
#endif // USE_OSD_SLAVE #endif // USE_OSD_SLAVE

View file

@ -511,7 +511,7 @@ void init(void)
// so we are ready to call validateAndFixGyroConfig(), pidInit(), and setAccelerationFilter() // so we are ready to call validateAndFixGyroConfig(), pidInit(), and setAccelerationFilter()
validateAndFixGyroConfig(); validateAndFixGyroConfig();
pidInit(currentPidProfile); pidInit(currentPidProfile);
setAccelerationFilter(accelerometerConfig()->acc_lpf_hz); accInitFilters();
#ifdef USE_SERVOS #ifdef USE_SERVOS
servosInit(); servosInit();

View file

@ -499,9 +499,9 @@ void setAccelerationTrims(flightDynamicsTrims_t *accelerationTrimsToUse)
accelerationTrims = accelerationTrimsToUse; accelerationTrims = accelerationTrimsToUse;
} }
void setAccelerationFilter(uint16_t initialAccLpfCutHz) void accInitFilters(void)
{ {
accLpfCutHz = initialAccLpfCutHz; accLpfCutHz = accelerometerConfig()->acc_lpf_hz;
if (acc.accSamplingInterval) { if (acc.accSamplingInterval) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterInitLPF(&accFilter[axis], accLpfCutHz, acc.accSamplingInterval); biquadFilterInitLPF(&accFilter[axis], accLpfCutHz, acc.accSamplingInterval);

View file

@ -80,4 +80,4 @@ void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims);
void accUpdate(rollAndPitchTrims_t *rollAndPitchTrims); void accUpdate(rollAndPitchTrims_t *rollAndPitchTrims);
union flightDynamicsTrims_u; union flightDynamicsTrims_u;
void setAccelerationTrims(union flightDynamicsTrims_u *accelerationTrimsToUse); void setAccelerationTrims(union flightDynamicsTrims_u *accelerationTrimsToUse);
void setAccelerationFilter(uint16_t initialAccLpfCutHz); void accInitFilters(void);