mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 13:25:30 +03:00
rename pid_ff
This commit is contained in:
parent
fde2aae4f5
commit
dc452ced00
1 changed files with 4 additions and 4 deletions
|
@ -638,13 +638,13 @@ void pidController(const pidProfile_t *pidProfile, const rollAndPitchTrims_t *an
|
||||||
pidData[axis].D = pidCoefficient[axis].Kd * delta * tpaFactor;
|
pidData[axis].D = pidCoefficient[axis].Kd * delta * tpaFactor;
|
||||||
|
|
||||||
|
|
||||||
const float pid_ff =
|
const float pidFeedForward =
|
||||||
pidCoefficient[axis].Kd * dynCd * transition *
|
pidCoefficient[axis].Kd * dynCd * transition *
|
||||||
(currentPidSetpoint - previousPidSetpoint[axis]) * tpaFactor / dT;
|
(currentPidSetpoint - previousPidSetpoint[axis]) * tpaFactor / dT;
|
||||||
if ((pidData[axis].P > 0) == (pid_ff > 0)) {
|
if ((pidData[axis].P > 0) == (pidFeedForward > 0)) {
|
||||||
if (ABS(pid_ff) > ABS(pidData[axis].P)) {
|
if (ABS(pidFeedForward) > ABS(pidData[axis].P)) {
|
||||||
pidData[axis].P = 0;
|
pidData[axis].P = 0;
|
||||||
pidData[axis].D += pid_ff;
|
pidData[axis].D += pidFeedForward;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue