1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-25 01:05:27 +03:00

Prevent ItermAccel and windup to clash with each other

This commit is contained in:
borisbstyle 2017-01-30 09:21:07 +01:00
parent 12a6d2f848
commit cf04294f70
4 changed files with 12 additions and 9 deletions

View file

@ -76,8 +76,9 @@ typedef struct pidProfile_s {
uint8_t levelSensitivity; // Angle mode sensitivity reflected in degrees assuming user using full stick
// Betaflight PID controller parameters
uint16_t itermThrottleThreshold; // max allowed throttle delta before errorGyroReset in ms
uint16_t itermThrottleThreshold; // max allowed throttle delta before iterm accelerated in ms
float itermAcceleratorGain; // Iterm Accelerator Gain when itermThrottlethreshold is hit
uint16_t itermAcceleratorRateLimit; // Setpointrate limit for iterm accelerator to operate within
uint8_t setpointRelaxRatio; // Setpoint weight relaxation effect
uint8_t dtermSetpointWeight; // Setpoint weight for Dterm (0= measurement, 1= full error, 1 > agressive derivative)
float yawRateAccelLimit; // yaw accel limiter for deg/sec/ms