warning:
In file included from ./src/main/sensors/gyro.c:1022:0:
./src/main/sensors/gyro_filter_impl.h: In function 'filterGyro':
./src/main/sensors/gyro_filter_impl.h:18:15: warning: variable 'gyroDataForAnalysis' set but not used
1. User can set sampling rate to suit expected range of frequencies:
- HIGH suits 4" or smaller and 6S 5"
- MEDIUM suits classic 5" 4S
- LOW is for 6" or greater
Limits automatically scaled:
HIGH : 133/166 to 1000Hz, MEDIUM : 89/111 to 666Hz, LOW : 67/83 to 500Hz
2. Bandpass entirely eliminated, not needed.
3. True peak detection method, favouring first peak to exceed 80% of maximum bin height; ignore or threshold values not required.
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.
For gyro loops from 2K to < 4K scale the FFT_SAMPLING_RATE_HZ to ensure we get 3 samples.
Also constrain the `centerFreq` result from the lowpass to ensure it doesn't overshoot beyond the min/max notch center cutoff.
Improves dynamic filter operation by providing a wider sampling window due to the higher gyro loop rate.
Makes the dynamic more useful by default on targets like SPRACINGF3.
Improves performance of the dynamic notch filter, increasing peak accuracy over a wider band of frequencies, and generally using a narrower, higher notch.
Details:
- FFT now operates on gyro data *after* gyro notches and lowpasses
- FFT bandpass Q changed from 0.707 to 0.05, to 'open up' the FFT to a greater range of incoming frequencies
- FFT centre output now ranges from about 130 to 666Hz.
- ignore the lowest couple of FFT bins going into centre frequency calculation
- analyse FFT bins from low to high, keep ignoring bins until a bin is found that exceeds its previous bin by a factor of 2; then start examining bins from the bin before that (stops the FFT from being biased low, or going to the lowest value if there is no notch at all).
- if no bin exceeds previous by more than 2 times, ie no obvious peak, smoothly go to maximum allowed notch frequency to avoid delay (might be better to bypass filter altogether?)
- dominant bin emphasised by cubing bin height before calculating mean
- maximum cutoff frequency is half the highest allowable centre frequency
- default notch width is +/-25% of centre, narrower than before most of the time
- code tidied up
- thanks to rav, Flint, UAV Tech, icr4sh, diehertz and everyone else who helped with this.
* will require coordination with BFC of course.
* rationale: previously `DEBUG_GYRO_NOTCH` debugging was used to grab the
scaled, unfiltered gyro readings, prior to the FFT running. This has been
updated to `DEBUG_GYRO_SCALED`.
similarly, `DEBUG_GYRO` debugging was used to record the filtered gyro. This
is updated to `GYRO_FILTERED`.
interestingly, `DEBUG_GYRO` was also used for movement threshold calibration.
This has been updated to be `DEBUG_GYRO_CALIBRATION` and also now stores
per-axis standard deviation.
Application of filter position moved slightly for logical grouping, has no
effect due to LTI.
* through extensive testing prior to the beginning of the RC cycle, we have
discovered that the simplest combination of filters appears to be up to four
PT1 filters: two for gyro, and two for d-term.
* non-cascaded biquad filter plumbing is retained for noisy setups and the
dynamic notch bandpass, although gyro and d-term variants of the filtering may
eventually be removed in favor of pt1
* update all related unit tests
Gryo calibration period can be configured in 1/100 second intervals using `gyro_calib_duration` (default is 125 or 1.25 seconds).
Renamed the `moron_threshold` parameter to `gyro_calib_noise_limit`. Functionally it is unchanged.
Data type and variable name cleanup.
Calculate the calibration sum using floats to prevent possibilities of future overflows.
Rename the calibratingG element to cyclesRemaining to be more representative of its purpose. Change its data type to int32_t to avoid calculations with signed and unsigned variables.
Fix the zero offset calculation from the calibration results to return a floating point result rather than using integer math. This may result in slight improvements in reduced gyro drift.
It seems like the gyro calibration sample count overflow fix (#5898) caused a downstream problem with the math to calculate the zero offset. Casting the components of the formula to (float) solves the problem.
The current data type was uint16 and that would overflow when using 32KHz sampling. This caused the calibration to only run for about 0.9 seconds instead of the expected 3 seconds. At 32KHz the sample count is 96774 which overflows uint16 so changed the data types to uint32.
Since we currently don't have per gyro configuration, trying to use two different gyro types simultaneously may not provide good results or lead to other unforeseen situations like attempting to initialize with settings not applicable to both hardware types.
This logic looks at the detected gyro types and resets to use only the first one if the user selected "BOTH" and they're different hardware types.
With the changes to add dual gyro support and the SPRACINGF7DUAL target, the defaulting logic of which gyro(s) to use was changed. The logic defaulted to using "BOTH" unless the target specifically selected a gyro.
I think this logic is backwards in that the first gyro should be selected by default unless the target specifies something different. The previous logic would cause all of the previous dual-gyro targets to default to "BOTH" even though they have different gyro types. This is probably not a good idea and definitely would cause an unexpected change for the users.
The SPRACINGF7DUAL target has two of the same gyro so defaulting to "BOTH" is appropriate. So now the target specifies that both gyros should be used in this case as the default.
* PID controller unittest
* Clean code for yaw spin recovery
* Yaw spin recovery optimizations
* Flash size optimizations, use 50% throttle when airmode is off, and override pidsum_limit_yaw
Also rebasing from betaflight/master
Previously the gyro_overflow_detect and fallback slew filter were based on target definitions to determine whether the flight controller had an affected gyro to enable protection. The problem is that some targets are available with multiple gyro options and if one of those options was an affected gyro then all flight controllers for that target would have the oveflow code enabled even if they had a non-affected gyro. Also targets that include multiple gyros on-board and are selectable at runtime were not differentiated and forced overflow handling on even if the selected gyro was not affected.
For non-affected gyros the overflow handling code is not required and reduces recovery performance so it's not desirable to have it enabled when unnecessary.
In the case of dual-gyro targets if gyro_to_use = BOTH then if either is an affected gyro then overflow handling will be enabled.
* Revert "Revert "Rewritten F7 dshot to LL (draft)" (#5430)"
This reverts commit aa42a69d2f.
* Reworked F7 linker scripts to maximize performance of both F74x and F72x
* Some comments and changes from original F7 HAL DSHOT
* Prohibit inlining of some functions to place them in ITCM-RAM
* Fixed usartTargetConfigure implicit declaration
* Moved back to SRAM1 as main RAM
* Added SRAM2 attribute
* Fixed LL DSHOT FOR SPRF7DUAL and probably other adv TIM users
* Fixed SPRF7DUAL rev. A motor order
* Enabled CCM for data on F40x
* Fixed F7 startup assembly symbols
* Fixed KISSFCV2F7 linker script
* Added a quick way of building F7 targets only
* Got rid of the useless F7 target script
* Added NOINLINE and got rid of useless __APPLE__ define
* Added some important functions to ITCM
* Added NOINLINE macro for tests
* Copy to ITCM before passing execution into it
* Minimized cache footprint of motor output code
* Evicted low-impact functions from ITCM
* Switched MATEKF722 and SPRACINGF7DUAL to burst DSHOT
* Switched CLRACINGF7 to burst DSHOT
* Moved UART RX&TX buffers to DTCM-RAM to avoid cache incoherency
* Marked taskMainPidLoop for ITCM-RAM, disallowed inlining per-function
* Revert "Added a quick way of building F7 targets only"
This reverts commit 2294518998.
The old gyro_lpf setting was based on the DLPF_CFG values for the MPU6050 gyro and the enumeration was inaccurate and misleading. For example, the default "OFF" setting did not disable the DLPF, but actually set it to around 250hz. The actual cutoff frequency for each setting varies by gyro hardware so the literal frequencies in the enumeration were also incorrect.
Removed gyro_lpf and replaced it with gyro_hardware_lpf (8KHz) and gyro_32khz_hardware_lpf (32KHz). The parameters were renamed to indicate that they are hardware filtering options to differentiate from the many software lowpass filtering options.
gyro_hardware_lpf - This parameter sets the filtering and sample rate options for 8KHz gyros (or 32KHz capable gyros running in 8KHz mode).
- NORMAL - default setting that is equivalent to the previous "OFF" setting. Configures 8KHz sampling with ~250Hz filter cutoff.
- EXPERIMENTAL - 8KHz sampling with a higher frequency filter cutoff (around 3000hz). Considerably more noisy and requires additional software filtering. Note that for the MPU6000 Invensense doesn't officially document the filter cutoff frequency for this selection and simply lists it as "reserved". In testing it's clear that a higher frequency filter cutoff is being selected due to the increased noise, but the actual cutoff frequency is unknown.
- 1KHZ_SAMPLING - 1KHz sample rate with and approximate 188Hz filter cutoff.
Note that the following additional 1KHz sample rate options with lower filter cutoffs have been eliminated - "98HZ", "42HZ", "20HZ", "10HZ", "5HZ". It seems unlikely that these are still needed are probably no longer viable and flight performance would be very poor.
gyro_32khz_hardware_lpf - This parameter sets the filtering options while running in 32KHz mode on capable gyros. It also exposes a new high frequency filter cutoff mode.
- NORMAL - The default and matches the current settings used for 32KHz mode. Provides a filter cutoff around 3000Hz.
- EXPERIMENTAL - Selects a filter cutoff around 8000Hz. This is a very noisy setting and will require substantial software filtering.
The default values for both 8KHz and 32KHz sample rates were chosen to match the previous defaults and users should not experience any performance differences.
Normalized the gyro initialization. Previously there was little consistency on how the initialization was performed and the settings interpreted. For example, MPU9250 used a completely different logic tree when configuring the registers.
Disconnected the literal parameter value from the gyro initialization. The gyro_lpf parameter contained a number from 0-7 that was literally applied to the configuration register during the gyro initialization. This caused some older gyro initializations to be incorrect as they used a different register layout (MPU3050 and L3G4200D). By transitioning to a logical selection the actual value applied to the hardware register is abstracted. This will better future-proof the design as new gyros may have a different register structure that may be incompatible with the old method.
Added a gyroregisters command to the CLI that is used to read the current register settings from the gyro and dump them to the CLI. This is used to verify the configuration in comparison to the datasheets for the various gyros. Testing empirically by looking at the relative noise from the gyros can give a rough estimate whether the different options are selecting correctly, but it's not very precise. The code for the gyroregisters CLI command is wrapped inside #ifdef USE_GYRO_REGISTER_DUMP blocks to allow easy disabling. It's currently enabled for all targets but we may decide to disable before release or only limit to targets with more available space (>=F4).
* Dual-stage Gyro Filtering: PT1, FKF, and Biquad RC+FIR2
* Builds on the previous work of apocolipse.
* Fixes 'stage2'/'stage1' mis-naming to reflect where it is applied in the loop.
That is, the older Biquad, PT1, Denoise (FIR) filters are 'stage2' - applied
after dynamic and static notches (if enabled), and the controversial PT1,
'fast Kalman' filter, and Biquad RC+FIR2 filters, are 'stage1'. e.g. before
dynamic notch.
* FKF bruteforce Kalman gain removed. Calculate from half of PT1 RC constant,
automatically taking loop-time into account.
* New union type definition for stage1 filtering.
* New gyro sensor members for stage1 filter application function and states for
all three supported filter types
* New enum types for stage1 v. stage2. dterm lowpass type references 'stage2'.
* updates to CMS/MSP/FC to allow compilation (untested, probably breaks
MSP, Lua, and ~comms with BFC~).
* Refactors FKF initialization, update and associated structures to be faster by
not continuously calculating 'k'. Filter gain is calculated once during
initialization from RC constant as per PT1 and Biquad RC+FIR2. It was
discovered this converges to static value within 100 samples at 32kHz, so can
be removed. Remove related interface (CLI) settings.
* update dterm_lowpass_type to use new 'TABLE_LOWPASS2_TYPE' (biquad/pt1/FIR)
* Stage 1 defaults to PT1, 763Hz (equivalent to Q400 / R88 from quasi-kalman
filter) - suitable for 32kHz sampling modes. Can be switched to Biquad
RC+FIR2, and FKF.
* Update `#if defined(USE_GYRO_SLEW_LIMITER) to `#ifdef`.
* Includes optional Lagged Moving Average 'smoothing' pipeline step, applied (in
code) after the output of stage1.
* (diehertz): Removed redundant pointers from gyro filtering
* blackbox: fix indentation
* cms IMU menu: fix indentation
* filters: remove USE_GYRO_FIR_FILTER_DENOISE in filter type enum
* gyro sensors: go back to `if defined()` form. for slew limiter
* gyro sensors: increment parameter group version
* due to non-appending changes, the version must be bumped.
* CF/BF - Set STM32F7 SPI FAST clock to 13.5Mhz - Gyros not stable at
27mhz.
* CF/BF - Initial SPRacingF7DUAL commit.
Support two simultaneous gyro support (code by Dominic Clifton and Martin Budden)
There are new debug modes so you can see the difference between each gyro.
Notes:
* spi bus instance caching broke spi mpu detection because the detection
tries I2C first which overwrites the selected bus instance when using
dual gyro.
* ALL other dual-gyro boards have one sensor per bus. SPRacingF7DUAL is has two per bus and thus commit has a lot of changes to fix SPI/BUS/GYRO initialisation issues.
* CF/BF - Add SPRacingF4EVODG target.
This target adds a second gyro to the board using the SPI pads on the back of the board.
* CF/BF - Temporarily disable Gyro EXTI pin to allow NEO target to build.