mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-26 01:35:41 +03:00
Added horizon_tilt_effect command
and horizon_tilt_expert_mode command. Modified 'calcHorizonLevelStrength()' function. Changed 'd_level' (D8[PIDLEVEL]) default from 100 to 75 Added horizon static float vars
This commit is contained in:
parent
2224347cbe
commit
8167892604
3 changed files with 74 additions and 11 deletions
|
@ -84,6 +84,9 @@ typedef struct pidProfile_s {
|
|||
uint8_t levelAngleLimit; // Max angle in degrees in level mode
|
||||
uint8_t levelSensitivity; // Angle mode sensitivity reflected in degrees assuming user using full stick
|
||||
|
||||
uint8_t horizon_tilt_effect; // inclination factor for Horizon mode
|
||||
uint8_t horizon_tilt_expert_mode; // OFF or ON
|
||||
|
||||
// Betaflight PID controller parameters
|
||||
uint16_t itermThrottleThreshold; // max allowed throttle delta before iterm accelerated in ms
|
||||
uint16_t itermAcceleratorGain; // Iterm Accelerator Gain when itermThrottlethreshold is hit
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue