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)
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
23 * 2018_07 updated by ctzsnooze to post filter, wider Q, different peak detection
24 * coding assistance and advice from DieHertz, Rav, eTracer
25 * test pilots icr4sh, UAV Tech, Flint723
27 * 2021_02 updated by KarateBrot: switched FFT with SDFT, multiple notches per axis
28 * test pilots: Sugar K, bizmar
35 #ifdef USE_GYRO_DATA_ANALYSE
36 #include "build/debug.h"
38 #include "common/filter.h"
39 #include "common/maths.h"
40 #include "common/sdft.h"
41 #include "common/time.h"
42 #include "common/utils.h"
44 #include "drivers/accgyro/accgyro.h"
45 #include "drivers/time.h"
47 #include "sensors/gyro.h"
51 #include "gyroanalyse.h"
53 // SDFT_SAMPLE_SIZE defaults to 72 (common/sdft.h).
54 // We get 36 frequency bins from 72 consecutive data values, called SDFT_BIN_COUNT (common/sdft.h)
55 // Bin 0 is DC and can't be used.
56 // Only bins 1 to 35 are usable.
58 // A gyro sample is collected every PID loop.
59 // maxSampleCount recent gyro values are accumulated and averaged
60 // to ensure that 72 samples are collected at the right rate for the required SDFT bandwidth.
62 // For an 8k PID loop, at default 600hz max, 6 sequential gyro data points are averaged, SDFT runs 1333Hz.
63 // Upper limit of SDFT is half that frequency, eg 666Hz by default.
64 // At 8k, if user sets a max of 300Hz, int(8000/600) = 13, sdftSampleRateHz = 615Hz, range 307Hz.
65 // Note that lower max requires more samples to be averaged, increasing precision but taking longer to get enough samples.
66 // For Bosch at 3200Hz gyro, max of 600, int(3200/1200) = 2, sdftSampleRateHz = 1600, range to 800hz.
67 // For Bosch on XClass, better to set a max of 300, int(3200/600) = 5, sdftSampleRateHz = 640, range to 320Hz.
69 // When sampleCount reaches maxSampleCount, the averaged gyro value is put into the corresponding SDFT.
70 // At 8k, with 600Hz max, maxSampleCount = 6, this happens every 6 * 0.125us, or every 0.75ms.
71 // Hence to completely replace all 72 samples of the SDFT input buffer with clean new data takes 54ms.
73 // The SDFT code is split into steps. It takes 4 PID loops to calculate the SDFT, track peaks and update the filters for one axis.
74 // Since there are three axes, it takes 12 PID loops to completely update all axes.
75 // At 8k, any one axis gets updated at 8000 / 12 or 666hz or every 1.5ms
76 // In this time, 2 points in the SDFT buffer will have changed.
77 // At 4k, it takes twice as long to update an axis, i.e. each axis updates only every 3ms.
78 // Four points in the buffer will have changed in that time, and each point will be the average of three samples.
79 // Hence output jitter at 4k is about four times worse than at 8k. At 2k output jitter is quite bad.
81 // Each SDFT output bin has width sdftSampleRateHz/72, ie 18.5Hz per bin at 1333Hz.
82 // Usable bandwidth is half this, ie 666Hz if sdftSampleRateHz is 1333Hz, i.e. bin 1 is 18.5Hz, bin 2 is 37.0Hz etc.
84 #define DYN_NOTCH_SMOOTH_HZ 4
85 #define DYN_NOTCH_CALC_TICKS (XYZ_AXIS_COUNT * STEP_COUNT) // 3 axes and 4 steps per axis
86 #define DYN_NOTCH_OSD_MIN_THROTTLE 20
92 STEP_CALC_FREQUENCIES
,
98 typedef struct peak_s
{
105 static sdft_t FAST_DATA_ZERO_INIT sdft
[XYZ_AXIS_COUNT
];
106 static peak_t FAST_DATA_ZERO_INIT peaks
[DYN_NOTCH_COUNT_MAX
];
107 static float FAST_DATA_ZERO_INIT sdftData
[SDFT_BIN_COUNT
];
108 static float FAST_DATA_ZERO_INIT sdftSampleRateHz
;
109 static float FAST_DATA_ZERO_INIT sdftResolutionHz
;
110 static int FAST_DATA_ZERO_INIT sdftStartBin
;
111 static int FAST_DATA_ZERO_INIT sdftEndBin
;
112 static float FAST_DATA_ZERO_INIT sdftMeanSq
;
113 static float FAST_DATA_ZERO_INIT dynNotchQ
;
114 static float FAST_DATA_ZERO_INIT dynNotchMinHz
;
115 static float FAST_DATA_ZERO_INIT dynNotchMaxHz
;
116 static uint16_t FAST_DATA_ZERO_INIT dynNotchMaxFFT
;
117 static float FAST_DATA_ZERO_INIT gain
;
118 static int FAST_DATA_ZERO_INIT numSamples
;
120 void gyroDataAnalyseInit(gyroAnalyseState_t
*state
, const uint32_t targetLooptimeUs
)
122 // initialise even if FEATURE_DYNAMIC_FILTER not set, since it may be set later
123 dynNotchQ
= gyroConfig()->dyn_notch_q
/ 100.0f
;
124 dynNotchMinHz
= gyroConfig()->dyn_notch_min_hz
;
125 dynNotchMaxHz
= MAX(2 * dynNotchMinHz
, gyroConfig()->dyn_notch_max_hz
);
127 // gyroDataAnalyse() is running at targetLoopRateHz (which is PID loop rate aka. 1e6f/gyro.targetLooptimeUs)
128 const float targetLoopRateHz
= 1.0f
/ targetLooptimeUs
* 1e6f
;
129 numSamples
= MAX(1, targetLoopRateHz
/ (2 * dynNotchMaxHz
)); // 600hz, 8k looptime, 6.00
131 sdftSampleRateHz
= targetLoopRateHz
/ numSamples
;
132 // eg 8k, user max 600hz, int(8000/1200) = 6 (6.666), sdftSampleRateHz = 1333hz, range 666Hz
133 // eg 4k, user max 600hz, int(4000/1200) = 3 (3.333), sdftSampleRateHz = 1333hz, range 666Hz
134 // eg 2k, user max 600hz, int(2000/1200) = 1 (1.666) sdftSampleRateHz = 2000hz, range 1000Hz
135 // eg 2k, user max 400hz, int(2000/800) = 2 (2.5) sdftSampleRateHz = 1000hz, range 500Hz
136 // eg 1k, user max 600hz, int(1000/1200) = 1 (max(1,0.8333)) sdftSampleRateHz = 1000hz, range 500Hz
137 // the upper limit of DN is always going to be the Nyquist frequency (= sampleRate / 2)
139 sdftResolutionHz
= sdftSampleRateHz
/ SDFT_SAMPLE_SIZE
; // 13.3hz per bin at 8k
140 sdftStartBin
= MAX(2, dynNotchMinHz
/ sdftResolutionHz
+ 0.5f
); // can't use bin 0 because it is DC.
141 sdftEndBin
= MIN(SDFT_BIN_COUNT
- 1, dynNotchMaxHz
/ sdftResolutionHz
+ 0.5f
); // can't use more than SDFT_BIN_COUNT bins.
142 gain
= pt1FilterGain(DYN_NOTCH_SMOOTH_HZ
, DYN_NOTCH_CALC_TICKS
/ targetLoopRateHz
); // minimum PT1 k value
144 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
145 sdftInit(&sdft
[axis
], sdftStartBin
, sdftEndBin
, numSamples
);
148 state
->maxSampleCount
= numSamples
;
149 state
->maxSampleCountRcp
= 1.0f
/ state
->maxSampleCount
;
151 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
152 for (int p
= 0; p
< gyro
.notchFilterDynCount
; p
++) {
153 // any init value is fine, but evenly spreading centerFreqs across frequency range makes notch filters stick to peaks quicker
154 state
->centerFreq
[axis
][p
] = (p
+ 0.5f
) * (dynNotchMaxHz
- dynNotchMinHz
) / (float)gyro
.notchFilterDynCount
+ dynNotchMinHz
;
159 // Collect gyro data, to be downsampled and analysed in gyroDataAnalyse() function
160 void gyroDataAnalysePush(gyroAnalyseState_t
*state
, const int axis
, const float sample
)
162 state
->oversampledGyroAccumulator
[axis
] += sample
;
165 static void gyroDataAnalyseUpdate(gyroAnalyseState_t
*state
);
167 // Downsample and analyse gyro data
168 FAST_CODE
void gyroDataAnalyse(gyroAnalyseState_t
*state
)
170 // samples should have been pushed by `gyroDataAnalysePush`
171 // if gyro sampling is > 1kHz, accumulate and average multiple gyro samples
172 if (state
->sampleCount
== state
->maxSampleCount
) {
173 state
->sampleCount
= 0;
175 // calculate mean value of accumulated samples
176 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
177 const float sample
= state
->oversampledGyroAccumulator
[axis
] * state
->maxSampleCountRcp
;
178 state
->downsampledGyroData
[axis
] = sample
;
180 DEBUG_SET(DEBUG_FFT
, 2, lrintf(sample
));
182 state
->oversampledGyroAccumulator
[axis
] = 0;
185 // We need DYN_NOTCH_CALC_TICKS ticks to update all axes with newly sampled value
186 // recalculation of filters takes 4 calls per axis => each filter gets updated every DYN_NOTCH_CALC_TICKS calls
187 // at 8kHz PID loop rate this means 8kHz / 4 / 3 = 666Hz => update every 1.5ms
188 // at 4kHz PID loop rate this means 4kHz / 4 / 3 = 333Hz => update every 3ms
189 state
->updateTicks
= DYN_NOTCH_CALC_TICKS
;
193 // SDFT processing in batches to synchronize with incoming downsampled data
194 for (int axis
= 0; axis
< XYZ_AXIS_COUNT
; axis
++) {
195 sdftPushBatch(&sdft
[axis
], state
->downsampledGyroData
[axis
], state
->sampleCount
);
197 state
->sampleCount
++;
199 // Find frequency peaks and update filters
200 if (state
->updateTicks
> 0) {
201 gyroDataAnalyseUpdate(state
);
202 --state
->updateTicks
;
206 // Find frequency peaks and update filters
207 static FAST_CODE_NOINLINE
void gyroDataAnalyseUpdate(gyroAnalyseState_t
*state
)
209 uint32_t startTime
= 0;
210 if (debugMode
== (DEBUG_FFT_TIME
)) {
211 startTime
= micros();
214 DEBUG_SET(DEBUG_FFT_TIME
, 0, state
->updateStep
);
216 switch (state
->updateStep
) {
218 case STEP_WINDOW
: // 6us @ F722
220 sdftWinSq(&sdft
[state
->updateAxis
], sdftData
);
222 // Calculate mean square over frequency range (= average power of vibrations)
224 for (int bin
= (sdftStartBin
+ 1); bin
< sdftEndBin
; bin
++) { // don't use startBin or endBin because they are not windowed properly
225 sdftMeanSq
+= sdftData
[bin
]; // sdftData is already squared (see sdftWinSq)
227 sdftMeanSq
/= sdftEndBin
- sdftStartBin
- 1;
229 DEBUG_SET(DEBUG_FFT_TIME
, 1, micros() - startTime
);
233 case STEP_DETECT_PEAKS
: // 6us @ F722
235 // Get memory ready for new peak data on current axis
236 for (int p
= 0; p
< gyro
.notchFilterDynCount
; p
++) {
238 peaks
[p
].value
= 0.0f
;
241 // Search for N biggest peaks in frequency spectrum
242 for (int bin
= (sdftStartBin
+ 1); bin
< sdftEndBin
; bin
++) {
243 // Check if bin is peak
244 if ((sdftData
[bin
] > sdftData
[bin
- 1]) && (sdftData
[bin
] > sdftData
[bin
+ 1])) {
245 // Check if peak is big enough to be one of N biggest peaks.
246 // If so, insert peak and sort peaks in descending height order
247 for (int p
= 0; p
< gyro
.notchFilterDynCount
; p
++) {
248 if (sdftData
[bin
] > peaks
[p
].value
) {
249 for (int k
= gyro
.notchFilterDynCount
- 1; k
> p
; k
--) {
250 peaks
[k
] = peaks
[k
- 1];
253 peaks
[p
].value
= sdftData
[bin
];
257 bin
++; // If bin is peak, next bin can't be peak => jump it
261 // Sort N biggest peaks in ascending bin order (example: 3, 8, 25, 0, 0, ..., 0)
262 for (int p
= gyro
.notchFilterDynCount
- 1; p
> 0; p
--) {
263 for (int k
= 0; k
< p
; k
++) {
264 // Swap peaks but ignore swapping void peaks (bin = 0). This leaves
265 // void peaks at the end of peaks array without moving them
266 if (peaks
[k
].bin
> peaks
[k
+ 1].bin
&& peaks
[k
+ 1].bin
!= 0) {
267 peak_t temp
= peaks
[k
];
268 peaks
[k
] = peaks
[k
+ 1];
274 DEBUG_SET(DEBUG_FFT_TIME
, 1, micros() - startTime
);
278 case STEP_CALC_FREQUENCIES
: // 4us @ F722
280 for (int p
= 0; p
< gyro
.notchFilterDynCount
; p
++) {
282 // Only update state->centerFreq if there is a peak (ignore void peaks) and if peak is above noise floor
283 if (peaks
[p
].bin
!= 0 && peaks
[p
].value
> sdftMeanSq
) {
285 float meanBin
= peaks
[p
].bin
;
287 // Height of peak bin (y1) and shoulder bins (y0, y2)
288 const float y0
= sdftData
[peaks
[p
].bin
- 1];
289 const float y1
= sdftData
[peaks
[p
].bin
];
290 const float y2
= sdftData
[peaks
[p
].bin
+ 1];
292 // Estimate true peak position aka. meanBin (fit parabola y(x) over y0, y1 and y2, solve dy/dx=0 for x)
293 const float denom
= 2.0f
* (y0
- 2 * y1
+ y2
);
295 meanBin
+= (y0
- y2
) / denom
;
298 // Convert bin to frequency: freq = bin * binResoultion (bin 0 is 0Hz)
299 const float centerFreq
= constrainf(meanBin
* sdftResolutionHz
, dynNotchMinHz
, dynNotchMaxHz
);
301 // PT1 style smoothing moves notch center freqs rapidly towards big peaks and slowly away, up to 8x faster
302 // DYN_NOTCH_SMOOTH_HZ = 4 & gainMultiplier = 1 .. 8 => PT1 -3dB cutoff frequency = 4Hz .. 41Hz
303 const float gainMultiplier
= constrainf(peaks
[p
].value
/ sdftMeanSq
, 1.0f
, 8.0f
);
305 // Finally update notch center frequency p on current axis
306 state
->centerFreq
[state
->updateAxis
][p
] += gain
* gainMultiplier
* (centerFreq
- state
->centerFreq
[state
->updateAxis
][p
]);
310 if(calculateThrottlePercentAbs() > DYN_NOTCH_OSD_MIN_THROTTLE
) {
311 for (int p
= 0; p
< gyro
.notchFilterDynCount
; p
++) {
312 dynNotchMaxFFT
= MAX(dynNotchMaxFFT
, state
->centerFreq
[state
->updateAxis
][p
]);
316 if (state
->updateAxis
== gyro
.gyroDebugAxis
) {
317 for (int p
= 0; p
< gyro
.notchFilterDynCount
&& p
< 3; p
++) {
318 DEBUG_SET(DEBUG_FFT_FREQ
, p
, lrintf(state
->centerFreq
[state
->updateAxis
][p
]));
320 DEBUG_SET(DEBUG_DYN_LPF
, 1, lrintf(state
->centerFreq
[state
->updateAxis
][0]));
323 DEBUG_SET(DEBUG_FFT_TIME
, 1, micros() - startTime
);
327 case STEP_UPDATE_FILTERS
: // 7us @ F722
329 for (int p
= 0; p
< gyro
.notchFilterDynCount
; p
++) {
330 // Only update notch filter coefficients if the corresponding peak got its center frequency updated in the previous step
331 if (peaks
[p
].bin
!= 0 && peaks
[p
].value
> sdftMeanSq
) {
332 biquadFilterUpdate(&gyro
.notchFilterDyn
[state
->updateAxis
][p
], state
->centerFreq
[state
->updateAxis
][p
], gyro
.targetLooptime
, dynNotchQ
, FILTER_NOTCH
);
336 DEBUG_SET(DEBUG_FFT_TIME
, 1, micros() - startTime
);
338 state
->updateAxis
= (state
->updateAxis
+ 1) % XYZ_AXIS_COUNT
;
342 state
->updateStep
= (state
->updateStep
+ 1) % STEP_COUNT
;
346 uint16_t getMaxFFT(void) {
347 return dynNotchMaxFFT
;
350 void resetMaxFFT(void) {
354 #endif // USE_GYRO_DATA_ANALYSE