mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 01:05:27 +03:00
Iterm reset rework // Airmode Iterm Protection Configurable // Dynamic Ki
New defaults
This commit is contained in:
parent
8149508352
commit
ff5c320b4a
12 changed files with 69 additions and 125 deletions
|
@ -22,7 +22,6 @@
|
|||
#define YAW_P_LIMIT_MIN 100 // Maximum value for yaw P limiter
|
||||
#define YAW_P_LIMIT_MAX 500 // Maximum value for yaw P limiter
|
||||
|
||||
#define YAW_ITERM_RESET_OFFSET 15 // May be made configurable in the future, but not really needed for yaw
|
||||
#define DYNAMIC_PTERM_STICK_THRESHOLD 400
|
||||
|
||||
typedef enum {
|
||||
|
@ -50,12 +49,6 @@ typedef enum {
|
|||
DELTA_FROM_MEASUREMENT
|
||||
} pidDeltaType_e;
|
||||
|
||||
typedef enum {
|
||||
RESET_DISABLE = 0,
|
||||
RESET_ITERM,
|
||||
RESET_ITERM_AND_REDUCE_PID
|
||||
} pidErrorResetOption_e;
|
||||
|
||||
typedef enum {
|
||||
SUPEREXPO_YAW_OFF = 0,
|
||||
SUPEREXPO_YAW_ON,
|
||||
|
@ -71,15 +64,13 @@ typedef struct pidProfile_s {
|
|||
uint8_t I8[PID_ITEM_COUNT];
|
||||
uint8_t D8[PID_ITEM_COUNT];
|
||||
|
||||
uint8_t itermResetOffset; // Reset offset for Iterm
|
||||
uint16_t dterm_lpf_hz; // Delta Filter in hz
|
||||
uint16_t yaw_lpf_hz; // Additional yaw filter when yaw axis too noisy
|
||||
uint16_t rollPitchItermResetRate; // Experimental threshold for resetting iterm for pitch and roll on certain rates
|
||||
uint8_t rollPitchItermResetAlways; // Reset Iterm also without SUPER EXPO
|
||||
uint16_t yawItermResetRate; // Experimental threshold for resetting iterm for yaw on certain rates
|
||||
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
|
||||
uint16_t yaw_p_limit;
|
||||
uint8_t dterm_average_count; // Configurable delta count for dterm
|
||||
uint8_t dynamic_pterm;
|
||||
uint8_t dynamic_pid; // Dynamic PID implementation (currently only P and I)
|
||||
|
||||
#ifdef GTUNE
|
||||
uint8_t gtune_lolimP[3]; // [0..200] Lower limit of P during G tune
|
||||
|
@ -98,10 +89,10 @@ typedef void (*pidControllerFuncPtr)(const pidProfile_t *pidProfile, const struc
|
|||
|
||||
extern int16_t axisPID[XYZ_AXIS_COUNT];
|
||||
extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
|
||||
bool antiWindupProtection;
|
||||
bool airmodeWasActivated;
|
||||
extern uint32_t targetPidLooptime;
|
||||
|
||||
void pidSetController(pidControllerType_e type);
|
||||
void pidResetErrorGyroState(uint8_t resetOption);
|
||||
void pidResetErrorGyroState(void);
|
||||
void setTargetPidLooptime(uint8_t pidProcessDenom);
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue