1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 00:35:39 +03:00

update antigravity for 4.4, no boost on yaw

Update to anti-gravity, including removal of the old Step mode, ability to adjust the P contribution (thanks @Limon), PT2 smoothed derivative model, inherent limiting of P boost during extremely fast stick travels to minimise P oscillations, less I during the middle of a throttle up, no I boost on yaw, add hz to cutoff labels

No antigravity on yaw, fix longstanding typo

h
This commit is contained in:
ctzsnooze 2022-06-20 08:55:31 +10:00
parent 4fa4d4851e
commit 6aaaf727ff
13 changed files with 92 additions and 160 deletions

View file

@ -54,10 +54,11 @@
#define ITERM_RELAX_CUTOFF_DEFAULT 15
// Anti gravity I constant
#define AG_KI 21.586988f;
#define ANTIGRAVITY_KI 0.34f; // if AG gain is 6, about 6 times iTerm will be added
#define ANTIGRAVITY_KP 0.0034f; // one fifth of the I gain on P by default
#define ITERM_ACCELERATOR_GAIN_OFF 0
#define ITERM_ACCELERATOR_GAIN_MAX 30000
#define ITERM_ACCELERATOR_GAIN_MAX 250
#define PID_ROLL_DEFAULT { 45, 80, 40, 120 }
#define PID_PITCH_DEFAULT { 47, 84, 46, 125 }
#define PID_YAW_DEFAULT { 45, 80, 0, 120 }
@ -101,11 +102,6 @@ typedef struct pidf_s {
uint16_t F;
} pidf_t;
typedef enum {
ANTI_GRAVITY_SMOOTH,
ANTI_GRAVITY_STEP
} antiGravityMode_e;
typedef enum {
ITERM_RELAX_OFF,
ITERM_RELAX_RP,
@ -149,9 +145,7 @@ typedef struct pidProfile_s {
uint8_t horizon_tilt_expert_mode; // OFF or ON
// Betaflight PID controller parameters
uint8_t antiGravityMode; // type of anti gravity method
uint16_t itermThrottleThreshold; // max allowed throttle delta before iterm accelerated in ms
uint16_t itermAcceleratorGain; // Iterm Accelerator Gain when itermThrottlethreshold is hit
uint8_t anti_gravity_gain; // AntiGravity Gain (was itermAcceleratorGain)
uint16_t yawRateAccelLimit; // yaw accel limiter for deg/sec/ms
uint16_t rateAccelLimit; // accel limiter roll/pitch deg/sec/ms
uint16_t crash_dthreshold; // dterm crash value
@ -226,6 +220,9 @@ typedef struct pidProfile_s {
uint8_t simplified_dterm_filter;
uint8_t simplified_dterm_filter_multiplier;
uint8_t simplified_pitch_pi_gain;
uint8_t anti_gravity_cutoff_hz;
uint8_t anti_gravity_p_gain;
} pidProfile_t;
PG_DECLARE_ARRAY(pidProfile_t, PID_PROFILE_COUNT, pidProfiles);
@ -279,14 +276,12 @@ typedef struct pidRuntime_s {
filterApplyFnPtr ptermYawLowpassApplyFn;
pt1Filter_t ptermYawLowpass;
bool antiGravityEnabled;
uint8_t antiGravityMode;
pt1Filter_t antiGravityThrottleLpf;
pt1Filter_t antiGravitySmoothLpf;
pt2Filter_t antiGravityLpf;
float antiGravityOsdCutoff;
float antiGravityThrottleHpf;
float antiGravityPBoost;
float antiGravityThrottleD;
float itermAccelerator;
uint16_t itermAcceleratorGain;
uint8_t antiGravityGain;
float antiGravityPGain;
pidCoefficient_t pidCoefficient[XYZ_AXIS_COUNT];
float levelGain;
float horizonGain;
@ -419,7 +414,6 @@ void pidSetAcroTrainerState(bool newState);
void pidUpdateTpaFactor(float throttle);
void pidUpdateAntiGravityThrottleFilter(float throttle);
bool pidOsdAntiGravityActive(void);
bool pidOsdAntiGravityMode(void);
void pidSetAntiGravityState(bool newState);
bool pidAntiGravityEnabled(void);