Fixes support for the multi-range method of configuring profile type adjustments that stopped working when "slots" were removed. Although this type of setup will now work again, the correct method is to have a single adjustment set to the full channel range.
Remove the giant `select` block that contained all the code to generate the elements and transition them to individual functions called only when the element is active. Simplifies the code and results in a performance improvement as it's not necessary to fall through the large `select` statement for every element that will be drawn. The individual functions and the element to function mapping are moved to a new `osd_elements.c` file.
Moved the OSD related code files to a new `osd/` directory.
Also pre-analyze the active elements and only process those that are active. This also saves processing as it's not necessary to loop through all 50 or so elements when only a couple are active.
Various other cleanup and removal of stale or unnecessary code.
In the default configuration the element drawing phase of the OSD task is reduced from ~51us to ~35us - resulting in about a 30% decrease in processing time.
Since we are limited to only 4 aux channels, it would be good to increase this count in order to allow more multiplexing of data into fewer aux channels. At 18 we can allow full PID editting for Roll+Pitch+Yaw using 1 aux channel. 24 leaves room above that... maybe 30 or 32 would be better?
Upped to 30 as per @etracer65's suggestion
increased PG_REGISTER_ARRAY version
Previously the logic would process all possible ranges defined by MAX_ADJUSTMENT_RANGE_COUNT even if some (or even all) ranges were not configured. This change first builds a list of configured ranges and only processes thos entries.
Reduces CPU load by skipping unnecessary processing and minimizes the impact of increasing the number of available ranges.
Renamed/repurposed the "D Setpoint" adjustment to be "Pitch & Roll F Adjustment" and have it simultaneously adjust pitch and roll.
Renamed the "D Setpoint Transition" adjustment to be "Feedforward Transition" - no functionality changes.
Added adjustments for the individual Pitch, Roll and Yaw axes.
Restructures the PID controller to decouple feedforward from D.
Cleaned up the structure of the PID controller; moved some feature-based enhancements out of the main structure.
Feedforward becomes a separate component of the PID controller and there is now:
f_pitch
f_roll
f_yaw
The default values of 60 for pitch and roll matches the default setpoint weight used in BF3.4. Yaw previously had no setpoint weight capability so the default here needs to be discussed. Currently it's also set to 60 and flight testing seems positive. Feedforward on yaw adds a lot of value so I don't think we want to default to 0. Instead we need decide on the default.
All occurences of setpoint weight have been replaced by feedforward. "setpoint_relax_ratio" has been renamed to "feedforward_transition".
The pidSum now consists of P + I + D + F.
D has been added back for yaw (disabled by default with d_yaw = 0). We've found little need for D for normal quads but it may have value for other configurations - particularly tricopters.
Updated CMS menus to support adjusting the feedforward for each axis.
Changed the default for "rc_interp_ch" to be "RPYT". Need yaw to be smoothed to support feedforward.
Open issues:
Needs BFC support
- Need to add support for the axis "F" gains.
- Remove "setpoint weight" slider.
- Rename "D Setpoint transition" to "Feedforward transition"
Needs BBE support
- Header "setpoint_relaxation_ratio" has been renamed "feedforward_transition"
- Header "dterm_setpoint_weight" has been replaced with an array named "feed_forward_weight".
example: H feed_forward_weight:65,60,60 (R,P,Y)
- PID component "AXISF" has been added for all axes. Should be handled like P, I and D values.
- PidSum calculation needs to include F.
Needs LUA script support
- Support the renamed "setpoint_relax_ratio".
- Support for feedforward weight on all 3 axes.
Open code issues:
- rc_adjustments.c - support for adjusting feedforward weight for all axes. Currently only supporting roll - needs coordination with BFC.
When the separate rc rates and rc expos for roll/pitch were added the descriptive names were never added to the OSD display strings array. Then later PID audio was added causing the array to be out of sync with the enumerated adjustment types. This led to a corrupted pointer reference in the OSD display.
Also the adjustment display name used for the OSD display was never initialized so the pointer was pointing to random memory.
Removed the use of globals and changed to use "getter" functions.
* Scale PIDs using aux channels
* Add control via variables and documentation
* Use USE_TXPID
* Removed OWNER_TXPID
* Use PWM_RANGE_MIDDLE
* Fix typos
* Move Tx PID arrays into pidProfile_t
* Move macro to pidUpdateRate function
* Enable TXPID on REVONANO
* Add support for direct setting of adjustments from aux channel
* Change variable name from adjustmentScale to adjustmentScale to avoid confusion
* Update documentation
* Change variable name from adjustmentScale to adjustmentScale to avoid confusion
* Only adjust settings if adjustment channel has changed value
* Fix formatting
* Use pidAudioModes_e type in ADJUSTMENT_PID_AUDIO setting. Only allow absolute override of settings of ADJUSTMENT_MODE_STEP.
* Add example 6
* Fix checking of adjustment mode
* Fix USE_PID_AUDIO code. Broke SPRACINGF7DUAL.