* Introduce CLI parameter gyro_filter_debug_axis which defaults to 'ROLL',
the previous behavior. When set to either PITCH, or YAW, the debug logging
implementation in the gyro filtering will use that axis instead.
When using external XJT it annoyingly beeps when A1 drops below 3.7v (72 out of 255). I removed frsky_spi_use_external_adc and added frsky_spi_a1_source = VBAT, EXTADC, CONST. To prevent XJT from beeping ever set CONST and XJT will assume that the "reciever" is powered with 5v. I messed up previous PR #7305 branch so I decided that it's easier to open a new one.
Closes#7297
Adds a new `tpa_mode` parameter that accepts `PD` (default) and `D`. Allows the user to configer to affect P/D as it always has, or switch to D-only mode.
Note: the `tpa_mode` parameter was added to the PID Profile instead of rate profiles with the other TPA parameters. This can be discussed, but I didn't think it made sense to have this be part of rate profiles as it affects PID tuning (the same argument could be made for the other TPA parameters).
Code is wrapped in `USE_TPA_MODE` so it can be disabled if needed.
Adds a race start assistance system that allows the pilot to pitch forward and then release the sticks with the quad holding position for the race start.
Officially Invensense lists the experimentl mode as "unsupported" on the MPU60x0 series. Previously it was added to allow testing. It's been determined that it's not a viable gyro filtering operational mode.
Also change "experimental" DLPF support available for F4 or higher. Few F3 boards have gyros that can use this mode anyway. Saves 200 bytes.
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.
Adds options to select the filter type for both input and derivative.
rc_smoothing_input_type = PT1 | BIQUAD (default is BIQUAD)
rc_smoothing_derivative_type = OFF | PT1 | BIQUAD (default is OFF)
Adds an additional rc channel smoothing algorithm that can be used in place of the default rc interpolation. Utilizing a filter-based approach the smoothing has lower latency and is immune to loop time jitter that can introduce artifacts. Additionally a smoothing filter is added to the setpoint derivative used to produce D-term setpoint weight resulting in a smoother effect on D.
The default setting is to use the previous interpolation logic and there are no changes unless the optional method is selected.
Configuration:
rc_smoothing_type: (INTERPOLATION | FILTER) - defaults to INTERPOLATION
rc_smoothing_input_hz: (0-255) - sets the rc channel input filter cutoff in Hz. Default value of 0 will enable auto calculation based on received RX frame rate.
rc_smoothing_derivative_hz: (0-255) - sets the setpoint weight derivative filter cutoff in Hz. Default value of 0 will enable auto calculation based on received RX frame rate.
rc_smoothing_debug_axis: (ROLL | PITCH | YAW | THROTTLE) - determines which axis is logged in the debug fields
Debug logging:
set debug_mode = RC_SMOOTHING
debug(0) = raw un-smoothed rc channel data
debug(1) = raw un-smoothed setpoint derivative
debug(2) = filtered setpoint derivative before applied to setpoint weight
debug(3) = auto-calculated filter cutoff frequency base after sampling the rx frame rate
Notes:
Currently only enabled for F4/F7 due to flash size limitations
Uses the rc_inter_ch parameter to determine which channels are smoothed (same as default interpolation logic)
The auto filter cutoff calculation will set a cutoff frequency of 30Hz for typical SBUS frames (9ms). 11ms Spektrum will calculate to approximately 25Hz. The user can manually enter the filter cutoffs to be used instead of the auto calculation. The current default calculation was chosen as a good starting point but may be adjusted in the future.
Setting a lower cutoff frequency will result in more smoothing, but also more delay.
There currently isn't any support for receivers that change their rx frame rate dynamically. So for CRSF users wishing to use this alternate smoothing method should change their settings to lock the rx frame rate for now. Support for auto-adjusting to new frame rates in flight will likely be added.
Adds a new angle limiting mode for pilots who are learning to fly in acro mode. Primarily targeted at new LOS acro pilots, but can be used with FPV as well.
The feature is activated with a new mode named "ACRO TRAINER". When the feature is active, the craft will fly in normal acro mode but will limit roll/pitch axes so that they don't exceed the configured angle limit. New pilots can start with a small angle limit and progressively increase as their skills improve.
The accelerometer must be enabled for the feature to be configured and function.
Also the feature will only be active while in acro flight and will disable if ANGLE or HORIZON modes are selected.
For most users all they need to do is simply configure the new mode to be active as desired on the "Modes" tab in the configurator and configure the desired angle limit in the cli.
Configuration parameters:
acro_trainer_angle_limit: (range 10-80) Angle limit in degrees.
acro_trainer_lookahead_ms: (range 10-200) Time in milliseconds that the logic will "look ahead" to help minimize overshoot and bounce-back if the limit is approached at high gyro rates. The default value of 50 should be good for most users. For low powered or unresponsive craft (micros or brushed) it may be helpful to increase this setting if you're seeing substantial overshoot.
acro_trainer_debug_axis: (ROLL, PITCH) The axis that will log information if debugging is active.
To enable debugging:
set debug_mode = ACRO_TRAINER
debug(0) - Current angle
debug(1) - The internal logic state
debug(2) - Modified setpoint
debug(3) - Projected angle based gyro rate and lookahead period
The `failsafe_kill_switch` parameter has been renamed to
`failsafe_switch_mode` and it determines what happens
when the Failsafe mode is activated with an AUX switch.
It takes one of three values:
0 - simulates RC signal loss - thus activates Stage1 failsafe
(former behavior when kill switch option was OFF)
1 - disarms immediately
(former behavior when kill switch option was ON)
2 - activates the failsafe procedure (Stage2) immediately (new)
Adds a new parameter mode `MODE_BITSET` that allows associating a cli parameter with a specific bit in a stored value. Bit packed values can be exposed with individual cli parameters for each bit as needed. Supports UINT8, UINT16 and newly added UINT32 data types (UINT32 not supported for other modes at this time).
Adds new throttle_limit_type and throttle_limit_percent parameters that allow the pilot to limit the maximum commanded throttle seen by the flight controller by either scaling or clipping the maximum throttle. The default is 100 representing no limiting. So as an example, if a pilot was to set throttle_limit_type = SCALE and throttle_limit_percent = 80 the throttle input would scale from 0 to 80% based on full stick deflection from the radio.
This capability replaces the method of limiting throttle in the radio which some pilots are using to manage throttle on tight courses or reduce overall battery consumption when the extra power isn't needed.
There is no effect on the maximum throttle seen by the motors so the mixer still has full authority.
Added a `USE_32K_CAPABLE_GYRO` define set in `common_fc_post.h` that replaces the repeated testing for each gyro define wherever 32KHz compatibility is checked.
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).
* Add ledstrip_grb_rgb setting (GRB or RGB) to handle WS2811 or WS2812 LED drivers
* Rename setting lookup table to lookupLedStripPackingOrder
* Fix call to ws2811UpdateStrip
* Fix unit test
* Use ledStripFormatRGB_e enumeration for RGB packing format
* Fix unit test
* Whoops. Make ledStripFormatRGB_e match lookupLedStripFormatRGB
* Applied review feedback
* Add documentation of ledstrip_grb_rgb
* 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.