mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 01:05:27 +03:00
Add ITerm anti-windup based on motor output saturation
Added noise threshold for PID ITerm accumulation Removed ITerm setpoint scaler. Added CLI and MSP settings Made default ITerm noise threshold zero. Added CLI setting. Removed itermWindupPointPercent from MSP
This commit is contained in:
parent
990c13b7ea
commit
9dfb3e45ee
8 changed files with 39 additions and 22 deletions
|
@ -66,8 +66,8 @@ typedef struct pidProfile_s {
|
|||
uint16_t yaw_lpf_hz; // Additional yaw filter when yaw axis too noisy
|
||||
uint16_t dterm_notch_hz; // Biquad dterm notch hz
|
||||
uint16_t dterm_notch_cutoff; // Biquad dterm notch low cutoff
|
||||
uint16_t rollPitchItermIgnoreRate; // Experimental threshold for resetting iterm for pitch and roll on certain rates
|
||||
uint16_t yawItermIgnoreRate; // Experimental threshold for resetting iterm for yaw on certain rates
|
||||
uint8_t itermWindupPointPercent; // Experimental ITerm windup threshold, percent motor saturation
|
||||
uint8_t itermNoiseThreshold; // Experimental ITerm noise threshold
|
||||
uint16_t yaw_p_limit;
|
||||
float pidSumLimit;
|
||||
uint8_t dterm_average_count; // Configurable delta count for dterm
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue