mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
Angle and Horizon Mode improvements (#12231)
* Angle and Horizon Update for 4.5 * BugFix FF noise Angle Mode on yaw and in level _race mode * use time constant in ms for angle feedforward smoothing * refactor to remove unnecessary definition --------- Co-authored-by: ChrisRosser <chrisrosser91@gmail.com>
This commit is contained in:
parent
d6ed53ecdf
commit
241e9a9b94
16 changed files with 482 additions and 271 deletions
|
@ -146,10 +146,10 @@ typedef struct pidProfile_s {
|
|||
uint16_t pidSumLimit;
|
||||
uint16_t pidSumLimitYaw;
|
||||
uint8_t pidAtMinThrottle; // Disable/Enable pids on zero throttle. Normally even without airmode P and D would be active.
|
||||
uint8_t levelAngleLimit; // Max angle in degrees in level mode
|
||||
uint8_t angle_limit; // Max angle in degrees in Angle mode
|
||||
|
||||
uint8_t horizon_tilt_effect; // inclination factor for Horizon mode
|
||||
uint8_t horizon_tilt_expert_mode; // OFF or ON
|
||||
uint8_t horizon_limit_degrees; // in Horizon mode, zero levelling when the quad's attitude exceeds this angle
|
||||
uint8_t horizon_ignore_sticks; // 0 = default, meaning both stick and attitude attenuation; 1 = only attitude attenuation
|
||||
|
||||
// Betaflight PID controller parameters
|
||||
uint8_t anti_gravity_gain; // AntiGravity Gain (was itermAcceleratorGain)
|
||||
|
@ -234,6 +234,8 @@ typedef struct pidProfile_s {
|
|||
uint8_t tpa_mode; // Controls which PID terms TPA effects
|
||||
uint8_t tpa_rate; // Percent reduction in P or D at full throttle
|
||||
uint16_t tpa_breakpoint; // Breakpoint where TPA is activated
|
||||
uint8_t angle_feedforward_smoothing_ms; // Smoothing factor for angle feedforward as time constant in milliseconds
|
||||
uint8_t angle_earth_ref; // Control amount of "co-ordination" from yaw into roll while pitched forward in angle mode
|
||||
} pidProfile_t;
|
||||
|
||||
PG_DECLARE_ARRAY(pidProfile_t, PID_PROFILE_COUNT, pidProfiles);
|
||||
|
@ -294,12 +296,12 @@ typedef struct pidRuntime_s {
|
|||
uint8_t antiGravityGain;
|
||||
float antiGravityPGain;
|
||||
pidCoefficient_t pidCoefficient[XYZ_AXIS_COUNT];
|
||||
float levelGain;
|
||||
float angleGain;
|
||||
float angleFeedforwardGain;
|
||||
float horizonGain;
|
||||
float horizonTransition;
|
||||
float horizonCutoffDegrees;
|
||||
float horizonFactorRatio;
|
||||
uint8_t horizonTiltExpertMode;
|
||||
float horizonLimitSticks;
|
||||
float horizonLimitDegrees;
|
||||
uint8_t horizonIgnoreSticks;
|
||||
float maxVelocity[XYZ_AXIS_COUNT];
|
||||
float itermWindupPointInv;
|
||||
bool inCrashRecoveryMode;
|
||||
|
@ -396,10 +398,18 @@ typedef struct pidRuntime_s {
|
|||
float feedforwardSmoothFactor;
|
||||
float feedforwardJitterFactor;
|
||||
float feedforwardBoostFactor;
|
||||
float angleFeedforward[XYZ_AXIS_COUNT];
|
||||
float angleTargetPrevious[XYZ_AXIS_COUNT];
|
||||
float angleTargetDelta[XYZ_AXIS_COUNT];
|
||||
uint8_t angleDuplicateCount[XYZ_AXIS_COUNT];
|
||||
#endif
|
||||
|
||||
#ifdef USE_ACC
|
||||
pt3Filter_t attitudeFilter[2]; // Only for ROLL and PITCH
|
||||
pt3Filter_t angleFeedforwardPt3[XYZ_AXIS_COUNT];
|
||||
float angleYawSetpoint;
|
||||
float angleEarthRef;
|
||||
float angleTarget[2];
|
||||
#endif
|
||||
} pidRuntime_t;
|
||||
|
||||
|
@ -446,7 +456,7 @@ void applyItermRelax(const int axis, const float iterm,
|
|||
void applyAbsoluteControl(const int axis, const float gyroRate, float *currentPidSetpoint, float *itermErrorRate);
|
||||
void rotateItermAndAxisError();
|
||||
float pidLevel(int axis, const pidProfile_t *pidProfile,
|
||||
const rollAndPitchTrims_t *angleTrim, float currentPidSetpoint, float horizonLevelStrength);
|
||||
const rollAndPitchTrims_t *angleTrim, float rawSetpoint, float horizonLevelStrength, bool newRcFrame);
|
||||
float calcHorizonLevelStrength(void);
|
||||
#endif
|
||||
void dynLpfDTermUpdate(float throttle);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue