mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
consistent gyro and dterm filter names
This commit is contained in:
parent
8702bba3ec
commit
99a7479b8c
16 changed files with 219 additions and 219 deletions
|
@ -37,7 +37,7 @@
|
|||
#define PIDSUM_LIMIT_MAX 1000
|
||||
|
||||
#define PID_GAIN_MAX 250
|
||||
#define F_GAIN_MAX 2000
|
||||
#define F_GAIN_MAX 1000
|
||||
#define D_MIN_GAIN_MAX 250
|
||||
|
||||
// Scaling factors for Pids for better tunable range in configurator for betaflight pid controller. The scaling is based on legacy pid controller or previous float
|
||||
|
@ -63,9 +63,9 @@
|
|||
#define PID_YAW_DEFAULT { 45, 80, 0, 120 }
|
||||
#define D_MIN_DEFAULT { 30, 30, 0 }
|
||||
|
||||
#define DYN_LPF_DTERM_MIN_HZ_DEFAULT 75
|
||||
#define DYN_LPF_DTERM_MAX_HZ_DEFAULT 150
|
||||
#define DTERM_LOWPASS_2_HZ_DEFAULT 150
|
||||
#define DTERM_LPF1_DYN_MIN_HZ_DEFAULT 75
|
||||
#define DTERM_LPF1_DYN_MAX_HZ_DEFAULT 150
|
||||
#define DTERM_LPF2_HZ_DEFAULT 150
|
||||
|
||||
typedef enum {
|
||||
PID_ROLL,
|
||||
|
@ -132,13 +132,13 @@ typedef enum feedforwardAveraging_e {
|
|||
|
||||
typedef struct pidProfile_s {
|
||||
uint16_t yaw_lowpass_hz; // Additional yaw filter when yaw axis too noisy
|
||||
uint16_t dterm_lowpass_hz; // Delta Filter in hz
|
||||
uint16_t dterm_lpf1_static_hz; // Static Dterm lowpass 1 filter cutoff value in hz
|
||||
uint16_t dterm_notch_hz; // Biquad dterm notch hz
|
||||
uint16_t dterm_notch_cutoff; // Biquad dterm notch low cutoff
|
||||
|
||||
pidf_t pid[PID_ITEM_COUNT];
|
||||
|
||||
uint8_t dterm_filter_type; // Filter selection for dterm
|
||||
uint8_t dterm_lpf1_type; // Filter type for dterm lowpass 1
|
||||
uint8_t itermWindupPointPercent; // iterm windup threshold, percent motor saturation
|
||||
uint16_t pidSumLimit;
|
||||
uint16_t pidSumLimitYaw;
|
||||
|
@ -163,7 +163,7 @@ typedef struct pidProfile_s {
|
|||
uint8_t crash_recovery_rate; // degree/second
|
||||
uint16_t crash_limit_yaw; // limits yaw errorRate, so crashes don't cause huge throttle increase
|
||||
uint16_t itermLimit;
|
||||
uint16_t dterm_lowpass2_hz; // Extra PT1 Filter on D in hz
|
||||
uint16_t dterm_lpf2_static_hz; // Static Dterm lowpass 2 filter cutoff value in hz
|
||||
uint8_t crash_recovery; // off, on, on and beeps when it is in crash recovery mode
|
||||
uint8_t throttle_boost; // how much should throttle be boosted during transient changes 0-100, 100 adds 10x hpf filtered throttle
|
||||
uint8_t throttle_boost_cutoff; // Which cutoff frequency to use for throttle boost. higher cutoffs keep the boost on for shorter. Specified in hz.
|
||||
|
@ -179,9 +179,9 @@ typedef struct pidProfile_s {
|
|||
uint8_t abs_control_limit; // Limit to the correction
|
||||
uint8_t abs_control_error_limit; // Limit to the accumulated error
|
||||
uint8_t abs_control_cutoff; // Cutoff frequency for path estimation in abs control
|
||||
uint8_t dterm_filter2_type; // Filter selection for 2nd dterm
|
||||
uint16_t dyn_lpf_dterm_min_hz;
|
||||
uint16_t dyn_lpf_dterm_max_hz;
|
||||
uint8_t dterm_lpf2_type; // Filter type for 2nd dterm lowpass
|
||||
uint16_t dterm_lpf1_dyn_min_hz; // Dterm lowpass filter 1 min hz when in dynamic mode
|
||||
uint16_t dterm_lpf1_dyn_max_hz; // Dterm lowpass filter 1 max hz when in dynamic mode
|
||||
uint8_t launchControlMode; // Whether launch control is limited to pitch only (launch stand or top-mount) or all axes (on battery)
|
||||
uint8_t launchControlThrottlePercent; // Throttle percentage to trigger launch for launch control
|
||||
uint8_t launchControlAngleLimit; // Optional launch control angle limit (requires ACC)
|
||||
|
@ -204,14 +204,14 @@ typedef struct pidProfile_s {
|
|||
uint8_t dyn_idle_d_gain; // D gain for corrections around rapid changes in rpm
|
||||
uint8_t dyn_idle_max_increase; // limit on maximum possible increase in motor idle drive during active control
|
||||
|
||||
uint8_t feedforward_transition; // Feedforward attenuation around centre sticks
|
||||
uint8_t feedforward_transition; // Feedforward attenuation around centre sticks
|
||||
uint8_t feedforward_averaging; // Number of packets to average when averaging is on
|
||||
uint8_t feedforward_smooth_factor; // Amount of lowpass type smoothing for feedforward steps
|
||||
uint8_t feedforward_jitter_factor; // Number of RC steps below which to attenuate feedforward
|
||||
uint8_t feedforward_boost; // amount of setpoint acceleration to add to feedforward, 10 means 100% added
|
||||
uint8_t feedforward_max_rate_limit; // Maximum setpoint rate percentage for feedforward
|
||||
|
||||
uint8_t dyn_lpf_curve_expo; // set the curve for dynamic dterm lowpass filter
|
||||
uint8_t dterm_lpf1_dyn_expo; // set the curve for dynamic dterm lowpass filter
|
||||
uint8_t level_race_mode; // NFE race mode - when true pitch setpoint calculation is gyro based in level mode
|
||||
uint8_t vbat_sag_compensation; // Reduce motor output by this percentage of the maximum compensation amount
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue