Skip to content

Commit ab4ff72

Browse files
committed
Add max FFT to OSD Summary
1 parent bc16e14 commit ab4ff72

File tree

6 files changed

+47
-1
lines changed

6 files changed

+47
-1
lines changed

src/main/fc/core.c

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,9 @@
5151
#include "sensors/boardalignment.h"
5252
#include "sensors/gyro.h"
5353
#include "sensors/sensors.h"
54-
54+
#if (!defined(SIMULATOR_BUILD) && !defined(UNIT_TEST))
55+
#include "sensors/gyroanalyse.h"
56+
#endif
5557
#include "fc/config.h"
5658
#include "fc/controlrate_profile.h"
5759
#include "fc/core.h"
@@ -437,6 +439,10 @@ void tryArm(void)
437439
}
438440
imuQuaternionHeadfreeOffsetSet();
439441

442+
#if (!defined(SIMULATOR_BUILD) && !defined(UNIT_TEST) && defined(USE_GYRO_DATA_ANALYSE))
443+
resetMaxFFT();
444+
#endif
445+
440446
disarmAt = currentTimeUs + armingConfig()->auto_disarm_delay * 1e6; // start disarm timeout, will be extended when throttle is nonzero
441447

442448
lastArmingDisabledReason = 0;

src/main/interface/settings.c

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1127,6 +1127,10 @@ const clivalue_t valueTable[] = {
11271127
{ "osd_stat_max_esc_rpm", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_STAT_MAX_ESC_RPM, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats)},
11281128
{ "osd_stat_min_link_quality", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_STAT_MIN_LINK_QUALITY,PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats)},
11291129
{ "osd_stat_flight_dist", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_STAT_FLIGHT_DISTANCE, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats)},
1130+
#ifdef USE_GYRO_DATA_ANALYSE
1131+
{ "osd_stat_max_fft", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_STAT_MAX_FFT, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats)},
1132+
#endif
1133+
11301134
#ifdef USE_OSD_PROFILES
11311135
{ "osd_profile", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, OSD_PROFILE_COUNT }, PG_OSD_CONFIG, offsetof(osdConfig_t, osdProfileIndex) },
11321136
#endif

src/main/io/osd.c

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,9 @@
9595
#include "sensors/battery.h"
9696
#include "sensors/esc_sensor.h"
9797
#include "sensors/sensors.h"
98+
#if (!defined(SIMULATOR_BUILD) && !defined(UNIT_TEST) && defined(USE_GYRO_DATA_ANALYSE))
99+
#include "sensors/gyroanalyse.h"
100+
#endif
98101

99102
#ifdef USE_HARDWARE_REVISION_DETECTION
100103
#include "hardware_revision.h"
@@ -1829,6 +1832,18 @@ static void osdShowStats(uint16_t endBatteryVoltage)
18291832
}
18301833
#endif
18311834

1835+
#if (!defined(SIMULATOR_BUILD) && !defined(UNIT_TEST) && defined(USE_GYRO_DATA_ANALYSE))
1836+
if (osdStatGetState(OSD_STAT_MAX_FFT) && featureIsEnabled(FEATURE_DYNAMIC_FILTER)) {
1837+
int value = getMaxFFT();
1838+
if (value > 0) {
1839+
tfp_sprintf(buff, "%dHZ", value);
1840+
osdDisplayStatisticLabel(top++, "PEAK FFT", buff);
1841+
} else {
1842+
osdDisplayStatisticLabel(top++, "PEAK FFT", "THRT<20%");
1843+
}
1844+
}
1845+
#endif
1846+
18321847
}
18331848

18341849
static void osdShowArmed(void)

src/main/io/osd.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -157,6 +157,7 @@ typedef enum {
157157
OSD_STAT_MAX_ESC_RPM,
158158
OSD_STAT_MIN_LINK_QUALITY,
159159
OSD_STAT_FLIGHT_DISTANCE,
160+
OSD_STAT_MAX_FFT,
160161
OSD_STAT_COUNT // MUST BE LAST
161162
} osd_stats_e;
162163

src/main/sensors/gyroanalyse.c

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,8 @@
4141
#include "sensors/gyro.h"
4242
#include "sensors/gyroanalyse.h"
4343

44+
#include "fc/core.h"
45+
4446
// The FFT splits the frequency domain into an number of bins
4547
// A sampling frequency of 1000 and max frequency of 500 at a window size of 32 gives 16 frequency bins each 31.25Hz wide
4648
// Eg [0,31), [31,62), [62, 93) etc
@@ -54,6 +56,8 @@
5456
// we need 4 steps for each axis
5557
#define DYN_NOTCH_CALC_TICKS (XYZ_AXIS_COUNT * 4)
5658

59+
#define DYN_NOTCH_OSD_MIN_THROTTLE 20
60+
5761
static uint16_t FAST_RAM_ZERO_INIT fftSamplingRateHz;
5862
static float FAST_RAM_ZERO_INIT fftResolution;
5963
static uint8_t FAST_RAM_ZERO_INIT fftBinOffset;
@@ -64,6 +68,7 @@ static float FAST_RAM_ZERO_INIT dynNotch1Ctr;
6468
static float FAST_RAM_ZERO_INIT dynNotch2Ctr;
6569
static uint16_t FAST_RAM_ZERO_INIT dynNotchMinHz;
6670
static bool FAST_RAM dualNotch = true;
71+
static uint16_t FAST_RAM_ZERO_INIT dynNotchMaxFFT;
6772

6873
// Hanning window, see https://en.wikipedia.org/wiki/Window_function#Hann_.28Hanning.29_window
6974
static FAST_RAM_ZERO_INIT float hanningWindow[FFT_WINDOW_SIZE];
@@ -323,6 +328,10 @@ static FAST_CODE_NOINLINE void gyroDataAnalyseUpdate(gyroAnalyseState_t *state,
323328
state->prevCenterFreq[state->updateAxis] = state->centerFreq[state->updateAxis];
324329
state->centerFreq[state->updateAxis] = centerFreq;
325330

331+
if(calculateThrottlePercentAbs() > DYN_NOTCH_OSD_MIN_THROTTLE) {
332+
dynNotchMaxFFT = MAX(dynNotchMaxFFT, state->centerFreq[state->updateAxis]);
333+
}
334+
326335
if (state->updateAxis == 0) {
327336
DEBUG_SET(DEBUG_FFT, 3, lrintf(fftMeanIndex * 100));
328337
DEBUG_SET(DEBUG_FFT_FREQ, 0, state->centerFreq[state->updateAxis]);
@@ -371,4 +380,13 @@ static FAST_CODE_NOINLINE void gyroDataAnalyseUpdate(gyroAnalyseState_t *state,
371380
state->updateStep = (state->updateStep + 1) % STEP_COUNT;
372381
}
373382

383+
384+
uint16_t getMaxFFT(void) {
385+
return dynNotchMaxFFT;
386+
}
387+
388+
void resetMaxFFT(void) {
389+
dynNotchMaxFFT = 0;
390+
}
391+
374392
#endif // USE_GYRO_DATA_ANALYSE

src/main/sensors/gyroanalyse.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -59,3 +59,5 @@ STATIC_ASSERT(FFT_WINDOW_SIZE <= (uint8_t) -1, window_size_greater_than_underlyi
5959
void gyroDataAnalyseStateInit(gyroAnalyseState_t *gyroAnalyse, uint32_t targetLooptime);
6060
void gyroDataAnalysePush(gyroAnalyseState_t *gyroAnalyse, int axis, float sample);
6161
void gyroDataAnalyse(gyroAnalyseState_t *gyroAnalyse, biquadFilter_t *notchFilterDyn, biquadFilter_t *notchFilterDyn2);
62+
uint16_t getMaxFFT(void);
63+
void resetMaxFFT(void);

0 commit comments

Comments
 (0)