mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 09:16:07 +03:00
major rc changes ctzsnooze 2021
This commit is contained in:
parent
2a5e457603
commit
636d563abe
26 changed files with 377 additions and 546 deletions
|
@ -121,13 +121,12 @@ typedef enum {
|
|||
ITERM_RELAX_TYPE_COUNT,
|
||||
} itermRelaxType_e;
|
||||
|
||||
typedef enum ffInterpolationType_e {
|
||||
FF_INTERPOLATE_OFF,
|
||||
FF_INTERPOLATE_ON,
|
||||
FF_INTERPOLATE_AVG2,
|
||||
FF_INTERPOLATE_AVG3,
|
||||
FF_INTERPOLATE_AVG4
|
||||
} ffInterpolationType_t;
|
||||
typedef enum feedforwardAveraging_e {
|
||||
FEEDFORWARD_AVERAGING_OFF,
|
||||
FEEDFORWARD_AVERAGING_2_POINT,
|
||||
FEEDFORWARD_AVERAGING_3_POINT,
|
||||
FEEDFORWARD_AVERAGING_4_POINT,
|
||||
} feedforwardAveraging_t;
|
||||
|
||||
#define MAX_PROFILE_NAME_LENGTH 8u
|
||||
|
||||
|
@ -162,7 +161,7 @@ typedef struct pidProfile_s {
|
|||
uint16_t crash_delay; // ms
|
||||
uint8_t crash_recovery_angle; // degrees
|
||||
uint8_t crash_recovery_rate; // degree/second
|
||||
uint8_t feedForwardTransition; // Feed forward weight transition
|
||||
uint8_t feedforwardTransition; // Feedforward attenuation around centre sticks
|
||||
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
|
||||
|
@ -198,7 +197,7 @@ typedef struct pidProfile_s {
|
|||
uint8_t motor_output_limit; // Upper limit of the motor output (percent)
|
||||
int8_t auto_profile_cell_count; // Cell count for this profile to be used with if auto PID profile switching is used
|
||||
uint8_t transient_throttle_limit; // Maximum DC component of throttle change to mix into throttle to prevent airmode mirroring noise
|
||||
uint8_t ff_boost; // amount of high-pass filtered FF to add to FF, 100 means 100% added
|
||||
uint8_t feedforward_boost; // amount of setpoint acceleration to add to feedforward, 10 means 100% added
|
||||
char profileName[MAX_PROFILE_NAME_LENGTH + 1]; // Descriptive name for profile
|
||||
|
||||
uint8_t dyn_idle_min_rpm; // minimum motor speed enforced by the dynamic idle controller
|
||||
|
@ -207,10 +206,10 @@ 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 ff_interpolate_sp; // Calculate FF from interpolated setpoint
|
||||
uint8_t ff_max_rate_limit; // Maximum setpoint rate percentage for FF
|
||||
uint8_t ff_smooth_factor; // Amount of smoothing for interpolated FF steps
|
||||
uint8_t ff_jitter_factor; // Number of RC steps below which to attenuate FF
|
||||
uint8_t feedforward_averaging; // Number of packets to average when averaging is on
|
||||
uint8_t feedforward_max_rate_limit; // Maximum setpoint rate percentage for feedforward
|
||||
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 dyn_lpf_curve_expo; // set the curve for dynamic dterm lowpass filter
|
||||
uint8_t level_race_mode; // NFE race mode - when true pitch setpoint calcualtion is gyro based in level mode
|
||||
uint8_t vbat_sag_compensation; // Reduce motor output by this percentage of the maximum compensation amount
|
||||
|
@ -222,7 +221,7 @@ typedef struct pidProfile_s {
|
|||
uint8_t simplified_pd_ratio;
|
||||
uint8_t simplified_pd_gain;
|
||||
uint8_t simplified_dmin_ratio;
|
||||
uint8_t simplified_ff_gain;
|
||||
uint8_t simplified_feedforward_gain;
|
||||
|
||||
uint8_t simplified_dterm_filter;
|
||||
uint8_t simplified_dterm_filter_multiplier;
|
||||
|
@ -286,7 +285,7 @@ typedef struct pidRuntime_s {
|
|||
float ffBoostFactor;
|
||||
float itermAccelerator;
|
||||
uint16_t itermAcceleratorGain;
|
||||
float feedForwardTransition;
|
||||
float feedforwardTransition;
|
||||
pidCoefficient_t pidCoefficient[XYZ_AXIS_COUNT];
|
||||
float levelGain;
|
||||
float horizonGain;
|
||||
|
@ -341,8 +340,8 @@ typedef struct pidRuntime_s {
|
|||
#endif
|
||||
|
||||
#ifdef USE_RC_SMOOTHING_FILTER
|
||||
pt3Filter_t setpointDerivativePt3[XYZ_AXIS_COUNT];
|
||||
bool setpointDerivativeLpfInitialized;
|
||||
pt3Filter_t feedforwardPt3[XYZ_AXIS_COUNT];
|
||||
bool feedforwardLpfInitialized;
|
||||
uint8_t rcSmoothingDebugAxis;
|
||||
uint8_t rcSmoothingFilterType;
|
||||
#endif // USE_RC_SMOOTHING_FILTER
|
||||
|
@ -383,8 +382,8 @@ typedef struct pidRuntime_s {
|
|||
float airmodeThrottleOffsetLimit;
|
||||
#endif
|
||||
|
||||
#ifdef USE_INTERPOLATED_SP
|
||||
ffInterpolationType_t ffFromInterpolatedSetpoint;
|
||||
#ifdef USE_FEEDFORWARD
|
||||
feedforwardAveraging_t feedforwardAveraging;
|
||||
float ffSmoothFactor;
|
||||
float ffJitterFactor;
|
||||
#endif
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue