Fix WS2812 led definition
[inav.git] / src / main / flight / gyroanalyse.c
blob16626f1dbe468db6b9fe754fcff12752adc708dd
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 /* original work by Rav
22 * 2018_07 updated by ctzsnooze to post filter, wider Q, different peak detection
23 * coding assistance and advice from DieHertz, Rav, eTracer
24 * test pilots icr4sh, UAV Tech, Flint723
26 #include <stdint.h>
28 #include "platform.h"
29 FILE_COMPILE_FOR_SPEED
31 #ifdef USE_DYNAMIC_FILTERS
33 #include "build/debug.h"
35 #include "common/filter.h"
36 #include "common/maths.h"
37 #include "common/time.h"
38 #include "common/utils.h"
39 #include "config/feature.h"
41 #include "drivers/accgyro/accgyro.h"
42 #include "drivers/time.h"
44 #include "sensors/gyro.h"
45 #include "fc/config.h"
47 #include "gyroanalyse.h"
49 enum {
50 STEP_ARM_CFFT_F32,
51 STEP_BITREVERSAL_AND_STAGE_RFFT_F32,
52 STEP_MAGNITUDE_AND_FREQUENCY,
53 STEP_UPDATE_FILTERS_AND_HANNING,
54 STEP_COUNT
57 // The FFT splits the frequency domain into an number of bins
58 // A sampling frequency of 1000 and max frequency of 500 at a window size of 32 gives 16 frequency bins each 31.25Hz wide
59 // Eg [0,31), [31,62), [62, 93) etc
60 // for gyro loop >= 4KHz, sample rate 2000 defines FFT range to 1000Hz, 16 bins each 62.5 Hz wide
61 // NB FFT_WINDOW_SIZE is set to 32 in gyroanalyse.h
62 #define FFT_BIN_COUNT (FFT_WINDOW_SIZE / 2)
63 // smoothing frequency for FFT centre frequency
64 #define DYN_NOTCH_SMOOTH_FREQ_HZ 25
67 * Slow down gyro sample acquisition. This lowers the max frequency but increases the resolution.
68 * On default 500us looptime and denominator 1, max frequency is 1000Hz with a resolution of 31.25Hz
69 * On default 500us looptime and denominator 2, max frequency is 500Hz with a resolution of 15.6Hz
71 #define FFT_SAMPLING_DENOMINATOR 2
73 void gyroDataAnalyseStateInit(
74 gyroAnalyseState_t *state,
75 uint16_t minFrequency,
76 uint32_t targetLooptimeUs
77 ) {
78 state->minFrequency = minFrequency;
80 state->fftSamplingRateHz = 1e6f / targetLooptimeUs / FFT_SAMPLING_DENOMINATOR;
81 state->maxFrequency = state->fftSamplingRateHz / 2; //max possible frequency is half the sampling rate
82 state->fftResolution = (float)state->maxFrequency / FFT_BIN_COUNT;
84 state->fftStartBin = state->minFrequency / lrintf(state->fftResolution);
86 for (int i = 0; i < FFT_WINDOW_SIZE; i++) {
87 state->hanningWindow[i] = (0.5f - 0.5f * cos_approx(2 * M_PIf * i / (FFT_WINDOW_SIZE - 1)));
90 arm_rfft_fast_init_f32(&state->fftInstance, FFT_WINDOW_SIZE);
92 // Frequency filter is executed every 12 cycles. 4 steps per cycle, 3 axises
93 const uint32_t filterUpdateUs = targetLooptimeUs * STEP_COUNT * XYZ_AXIS_COUNT;
95 for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
97 for (int i = 0; i < DYN_NOTCH_PEAK_COUNT; i++) {
98 state->centerFrequency[axis][i] = state->maxFrequency;
99 pt1FilterInit(&state->detectedFrequencyFilter[axis][i], DYN_NOTCH_SMOOTH_FREQ_HZ, US2S(filterUpdateUs));
105 void gyroDataAnalysePush(gyroAnalyseState_t *state, const int axis, const float sample)
107 state->currentSample[axis] = sample;
110 static void gyroDataAnalyseUpdate(gyroAnalyseState_t *state);
113 * Collect gyro data, to be analysed in gyroDataAnalyseUpdate function
115 void gyroDataAnalyse(gyroAnalyseState_t *state)
117 state->filterUpdateExecute = false; //This will be changed to true only if new data is present
119 static uint8_t samplingIndex = 0;
121 if (samplingIndex == 0) {
122 // calculate mean value of accumulated samples
123 for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
124 state->downsampledGyroData[axis][state->circularBufferIdx] = state->currentSample[axis];
127 state->circularBufferIdx = (state->circularBufferIdx + 1) % FFT_WINDOW_SIZE;
130 samplingIndex = (samplingIndex + 1) % FFT_SAMPLING_DENOMINATOR;
132 gyroDataAnalyseUpdate(state);
135 void stage_rfft_f32(arm_rfft_fast_instance_f32 *S, float32_t *p, float32_t *pOut);
136 void arm_cfft_radix8by4_f32(arm_cfft_instance_f32 *S, float32_t *p1);
137 void arm_bitreversal_32(uint32_t *pSrc, const uint16_t bitRevLen, const uint16_t *pBitRevTable);
139 static float computeParabolaMean(gyroAnalyseState_t *state, uint8_t peakBinIndex) {
140 float preciseBin = peakBinIndex;
142 // Height of peak bin (y1) and shoulder bins (y0, y2)
143 const float y0 = state->fftData[peakBinIndex - 1];
144 const float y1 = state->fftData[peakBinIndex];
145 const float y2 = state->fftData[peakBinIndex - 1];
147 // Estimate true peak position aka. preciseBin (fit parabola y(x) over y0, y1 and y2, solve dy/dx=0 for x)
148 const float denom = 2.0f * (y0 - 2 * y1 + y2);
149 if (denom != 0.0f) {
150 //Cap precise bin to prevent off values if parabola is not fitted correctly
151 preciseBin += constrainf((y0 - y2) / denom, -0.5f, 0.5f);
154 return preciseBin;
158 * Analyse last gyro data from the last FFT_WINDOW_SIZE milliseconds
160 static NOINLINE void gyroDataAnalyseUpdate(gyroAnalyseState_t *state)
163 arm_cfft_instance_f32 *Sint = &(state->fftInstance.Sint);
165 switch (state->updateStep) {
166 case STEP_ARM_CFFT_F32:
168 // Important this works only with FFT windows size of 64 elements!
169 arm_cfft_radix8by4_f32(Sint, state->fftData);
170 break;
172 case STEP_BITREVERSAL_AND_STAGE_RFFT_F32:
174 arm_bitreversal_32((uint32_t*) state->fftData, Sint->bitRevLength, Sint->pBitRevTable);
175 stage_rfft_f32(&state->fftInstance, state->fftData, state->rfftData);
176 break;
178 case STEP_MAGNITUDE_AND_FREQUENCY:
180 // 8us
181 arm_cmplx_mag_f32(state->rfftData, state->fftData, FFT_BIN_COUNT);
183 //Zero the data structure
184 for (int i = 0; i < DYN_NOTCH_PEAK_COUNT; i++) {
185 state->peaks[i].bin = 0;
186 state->peaks[i].value = 0.0f;
189 // Find peaks
190 for (int bin = (state->fftStartBin + 1); bin < FFT_BIN_COUNT - 1; bin++) {
192 * Peak is defined if the current bin is greater than the previous bin and the next bin
194 if (
195 state->fftData[bin] > state->fftData[bin - 1] &&
196 state->fftData[bin] > state->fftData[bin + 1]
199 * We are only interested in N biggest peaks
200 * Check previously found peaks and update the structure if necessary
202 for (int p = 0; p < DYN_NOTCH_PEAK_COUNT; p++) {
203 if (state->fftData[bin] > state->peaks[p].value) {
204 for (int k = DYN_NOTCH_PEAK_COUNT - 1; k > p; k--) {
205 state->peaks[k] = state->peaks[k - 1];
207 state->peaks[p].bin = bin;
208 state->peaks[p].value = state->fftData[bin];
209 break;
212 bin++; // If bin is peak, next bin can't be peak => jump it
216 // Sort N biggest peaks in ascending bin order (example: 3, 8, 25, 0, 0, ..., 0)
217 for (int p = DYN_NOTCH_PEAK_COUNT - 1; p > 0; p--) {
218 for (int k = 0; k < p; k++) {
219 // Swap peaks but ignore swapping void peaks (bin = 0). This leaves
220 // void peaks at the end of peaks array without moving them
221 if (state->peaks[k].bin > state->peaks[k + 1].bin && state->peaks[k + 1].bin != 0) {
222 peak_t temp = state->peaks[k];
223 state->peaks[k] = state->peaks[k + 1];
224 state->peaks[k + 1] = temp;
229 break;
231 case STEP_UPDATE_FILTERS_AND_HANNING:
235 * Update frequencies
237 for (int i = 0; i < DYN_NOTCH_PEAK_COUNT; i++) {
239 if (state->peaks[i].bin > 0) {
240 const int bin = constrain(state->peaks[i].bin, state->fftStartBin, FFT_BIN_COUNT - 1);
241 float frequency = computeParabolaMean(state, bin) * state->fftResolution;
243 state->centerFrequency[state->updateAxis][i] = pt1FilterApply(&state->detectedFrequencyFilter[state->updateAxis][i], frequency);
244 } else {
245 state->centerFrequency[state->updateAxis][i] = 0.0f;
250 * Filters will be updated inside dynamicGyroNotchFiltersUpdate()
252 state->filterUpdateExecute = true;
253 state->filterUpdateAxis = state->updateAxis;
255 //Switch to the next axis
256 state->updateAxis = (state->updateAxis + 1) % XYZ_AXIS_COUNT;
258 // apply hanning window to gyro samples and store result in fftData
259 // hanning starts and ends with 0, could be skipped for minor speed improvement
260 arm_mult_f32(state->downsampledGyroData[state->updateAxis], state->hanningWindow, state->fftData, FFT_WINDOW_SIZE);
264 state->updateStep = (state->updateStep + 1) % STEP_COUNT;
267 #endif // USE_DYNAMIC_FILTERS