optimize math (#5287)
[betaflight.git] / src / main / common / filter.h
blob8744f889bd097d7e7aaa95c57a896019862ae4d3
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #pragma once
20 // Don't use it on F1 and F3 to lower RAM usage
21 // FIR/Denoise filter can be cleaned up in the future as it is rarely used and used to be experimental
22 #if (defined(STM32F1) || defined(STM32F3))
23 #define MAX_FIR_DENOISE_WINDOW_SIZE 1
24 #else
25 #define MAX_FIR_DENOISE_WINDOW_SIZE 120
26 #endif
28 struct filter_s;
29 typedef struct filter_s filter_t;
31 typedef struct pt1Filter_s {
32 float state;
33 float k;
34 } pt1Filter_t;
36 typedef struct slewFilter_s {
37 float state;
38 float slewLimit;
39 float threshold;
40 } slewFilter_t;
42 /* this holds the data required to update samples thru a filter */
43 typedef struct biquadFilter_s {
44 float b0, b1, b2, a1, a2;
45 float x1, x2, y1, y2;
46 } biquadFilter_t;
48 typedef struct firFilterDenoise_s {
49 int filledCount;
50 int targetCount;
51 int index;
52 float movingSum;
53 float state[MAX_FIR_DENOISE_WINDOW_SIZE];
54 } firFilterDenoise_t;
56 typedef struct fastKalman_s {
57 float q; // process noise covariance
58 float r; // measurement noise covariance
59 float p; // estimation error covariance matrix
60 float k; // kalman gain
61 float x; // state
62 float lastX; // previous state
63 } fastKalman_t;
65 typedef enum {
66 FILTER_PT1 = 0,
67 FILTER_BIQUAD,
68 FILTER_FIR,
69 FILTER_SLEW
70 } filterType_e;
72 typedef enum {
73 FILTER_LPF,
74 FILTER_NOTCH,
75 FILTER_BPF,
76 } biquadFilterType_e;
78 typedef struct firFilter_s {
79 float *buf;
80 const float *coeffs;
81 float movingSum;
82 uint8_t index;
83 uint8_t count;
84 uint8_t bufLength;
85 uint8_t coeffsLength;
86 } firFilter_t;
88 typedef float (*filterApplyFnPtr)(filter_t *filter, float input);
90 float nullFilterApply(filter_t *filter, float input);
92 void biquadFilterInitLPF(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate);
93 void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, biquadFilterType_e filterType);
94 void biquadFilterUpdate(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, biquadFilterType_e filterType);
95 float biquadFilterApplyDF1(biquadFilter_t *filter, float input);
96 float biquadFilterApply(biquadFilter_t *filter, float input);
97 float filterGetNotchQ(uint16_t centerFreq, uint16_t cutoff);
99 void biquadRCFIR2FilterInit(biquadFilter_t *filter, uint16_t f_cut, float dT);
101 void fastKalmanInit(fastKalman_t *filter, float q, float r, float p);
102 float fastKalmanUpdate(fastKalman_t *filter, float input);
104 // not exactly correct, but very very close and much much faster
105 #define filterGetNotchQApprox(centerFreq, cutoff) ((float)(cutoff * centerFreq) / ((float)(centerFreq - cutoff) * (float)(centerFreq + cutoff)))
107 void pt1FilterInit(pt1Filter_t *filter, uint8_t f_cut, float dT);
108 float pt1FilterApply(pt1Filter_t *filter, float input);
110 void slewFilterInit(slewFilter_t *filter, float slewLimit, float threshold);
111 float slewFilterApply(slewFilter_t *filter, float input);
113 void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs);
114 void firFilterInit2(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs, uint8_t coeffsLength);
115 void firFilterUpdate(firFilter_t *filter, float input);
116 void firFilterUpdateAverage(firFilter_t *filter, float input);
117 float firFilterApply(const firFilter_t *filter);
118 float firFilterUpdateAndApply(firFilter_t *filter, float input);
119 float firFilterCalcPartialAverage(const firFilter_t *filter, uint8_t count);
120 float firFilterCalcMovingAverage(const firFilter_t *filter);
121 float firFilterLastInput(const firFilter_t *filter);
123 void firFilterDenoiseInit(firFilterDenoise_t *filter, uint8_t gyroSoftLpfHz, uint16_t targetLooptime);
124 float firFilterDenoiseUpdate(firFilterDenoise_t *filter, float input);