1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00
betaflight/src/main/interface/settings.h
ctzsnooze 1e960c95eb Dynamic Filter Update
Improves on earlier 3.5RC1 dynamic filter with:
- better FFT tracking performance overall, even with a narrower default notch width
- can reach 850Hz for high kV 2.5-3" and 6S quads
- works better with 32k gyros
- can be applied pre- (location 1) and post- (location 2) static filters. Pre-static filter location works best, but post-static may work well in 32k modes or with PT1 option
- option to use a PT1 filter rather than the classical notch filter, perhaps useful for quads with a lot of noise above their peak.
- ability to totally bypass the pre-FFT bandpass filter, by setting Q=0, maximising the range of responsiveness
- "ignore" value, absolute FFT bin amplitude below which the bin will be excluded from consideration. May be tweaked to optimise peak detection; primarily for advanced tuners. If too high, only the very peaks will be included, if too low, noise may clutter peak detection.
- "threshold" value for peak detection, which, when divided by 10, is the multiple by which one bin must exceed the previous one for peak detection to commence. If too low, FFT detection becomes more random, if too high, no peaks are detected.
2018-08-20 00:33:10 +10:00

204 lines
5 KiB
C

/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <stdint.h>
#include <stdbool.h>
#include "pg/pg.h"
typedef enum {
TABLE_OFF_ON = 0,
TABLE_UNIT,
TABLE_ALIGNMENT,
#ifdef USE_GPS
TABLE_GPS_PROVIDER,
TABLE_GPS_SBAS_MODE,
#endif
#ifdef USE_GPS_RESCUE
TABLE_GPS_RESCUE,
#endif
#ifdef USE_BLACKBOX
TABLE_BLACKBOX_DEVICE,
TABLE_BLACKBOX_MODE,
#endif
TABLE_CURRENT_METER,
TABLE_VOLTAGE_METER,
#ifdef USE_SERVOS
TABLE_GIMBAL_MODE,
#endif
#ifdef USE_SERIAL_RX
TABLE_SERIAL_RX,
#endif
#ifdef USE_RX_SPI
TABLE_RX_SPI,
#endif
TABLE_GYRO_HARDWARE_LPF,
#ifdef USE_32K_CAPABLE_GYRO
TABLE_GYRO_32KHZ_HARDWARE_LPF,
#endif
TABLE_ACC_HARDWARE,
#ifdef USE_BARO
TABLE_BARO_HARDWARE,
#endif
#ifdef USE_MAG
TABLE_MAG_HARDWARE,
#endif
TABLE_DEBUG,
TABLE_MOTOR_PWM_PROTOCOL,
TABLE_RC_INTERPOLATION,
TABLE_RC_INTERPOLATION_CHANNELS,
TABLE_LOWPASS_TYPE,
TABLE_DTERM_LOWPASS_TYPE,
TABLE_ANTI_GRAVITY_MODE,
TABLE_FAILSAFE,
TABLE_FAILSAFE_SWITCH_MODE,
TABLE_CRASH_RECOVERY,
#ifdef USE_CAMERA_CONTROL
TABLE_CAMERA_CONTROL_MODE,
#endif
TABLE_BUS_TYPE,
#ifdef USE_MAX7456
TABLE_MAX7456_CLOCK,
#endif
#ifdef USE_RANGEFINDER
TABLE_RANGEFINDER_HARDWARE,
#endif
#ifdef USE_GYRO_OVERFLOW_CHECK
TABLE_GYRO_OVERFLOW_CHECK,
#endif
TABLE_RATES_TYPE,
#ifdef USE_OVERCLOCK
TABLE_OVERCLOCK,
#endif
#ifdef USE_LED_STRIP
TABLE_RGB_GRB,
#endif
#ifdef USE_DUAL_GYRO
TABLE_GYRO,
#endif
TABLE_THROTTLE_LIMIT_TYPE,
#ifdef USE_MAX7456
TABLE_VIDEO_SYSTEM,
#endif // USE_MAX7456
#if defined(USE_ITERM_RELAX)
TABLE_ITERM_RELAX,
TABLE_ITERM_RELAX_TYPE,
#endif
#ifdef USE_ACRO_TRAINER
TABLE_ACRO_TRAINER_DEBUG,
#endif // USE_ACRO_TRAINER
#ifdef USE_RC_SMOOTHING_FILTER
TABLE_RC_SMOOTHING_TYPE,
TABLE_RC_SMOOTHING_DEBUG,
TABLE_RC_SMOOTHING_INPUT_TYPE,
TABLE_RC_SMOOTHING_DERIVATIVE_TYPE,
#endif // USE_RC_SMOOTHING_FILTER
#ifdef USE_GYRO_DATA_ANALYSE
TABLE_DYNAMIC_FILTER_LOCATION,
#endif // USE_GYRO_DATA_ANALYSE
LOOKUP_TABLE_COUNT
} lookupTableIndex_e;
typedef struct lookupTableEntry_s {
const char * const *values;
const uint8_t valueCount;
} lookupTableEntry_t;
#define VALUE_TYPE_OFFSET 0
#define VALUE_SECTION_OFFSET 3
#define VALUE_MODE_OFFSET 5
typedef enum {
// value type, bits 0-2
VAR_UINT8 = (0 << VALUE_TYPE_OFFSET),
VAR_INT8 = (1 << VALUE_TYPE_OFFSET),
VAR_UINT16 = (2 << VALUE_TYPE_OFFSET),
VAR_INT16 = (3 << VALUE_TYPE_OFFSET),
VAR_UINT32 = (4 << VALUE_TYPE_OFFSET),
// value section, bits 3-4
MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
PROFILE_RATE_VALUE = (2 << VALUE_SECTION_OFFSET),
// value mode, bits 5-6
MODE_DIRECT = (0 << VALUE_MODE_OFFSET),
MODE_LOOKUP = (1 << VALUE_MODE_OFFSET),
MODE_ARRAY = (2 << VALUE_MODE_OFFSET),
MODE_BITSET = (3 << VALUE_MODE_OFFSET)
} cliValueFlag_e;
#define VALUE_TYPE_MASK (0x07)
#define VALUE_SECTION_MASK (0x18)
#define VALUE_MODE_MASK (0x60)
typedef struct cliMinMaxConfig_s {
const int16_t min;
const int16_t max;
} cliMinMaxConfig_t;
typedef struct cliLookupTableConfig_s {
const lookupTableIndex_e tableIndex;
} cliLookupTableConfig_t;
typedef struct cliArrayLengthConfig_s {
const uint8_t length;
} cliArrayLengthConfig_t;
typedef union {
cliLookupTableConfig_t lookup;
cliMinMaxConfig_t minmax;
cliArrayLengthConfig_t array;
uint8_t bitpos;
} cliValueConfig_t;
typedef struct clivalue_s {
const char *name;
const uint8_t type; // see cliValueFlag_e
const cliValueConfig_t config;
pgn_t pgn;
uint16_t offset;
} __attribute__((packed)) clivalue_t;
extern const lookupTableEntry_t lookupTables[];
extern const uint16_t valueTableEntryCount;
extern const clivalue_t valueTable[];
//extern const uint8_t lookupTablesEntryCount;
extern const char * const lookupTableGyroHardware[];
extern const char * const lookupTableAccHardware[];
//extern const uint8_t lookupTableAccHardwareEntryCount;
extern const char * const lookupTableBaroHardware[];
//extern const uint8_t lookupTableBaroHardwareEntryCount;
extern const char * const lookupTableMagHardware[];
//extern const uint8_t lookupTableMagHardwareEntryCount;
extern const char * const lookupTableRangefinderHardware[];