mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 23:05:19 +03:00
Fix wrong filter selection and Scaling in Rewrite
This commit is contained in:
parent
e0e7db74f1
commit
b6e0927f96
2 changed files with 3 additions and 4 deletions
|
@ -364,7 +364,7 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat
|
|||
|
||||
filterApplyFIR(&delta, deltaFIRState[axis], deltaFIRTable);
|
||||
|
||||
DTerm = (delta * 2 * pidProfile->D8[axis] * PIDweight[axis] / 100) >> 8;
|
||||
DTerm = (delta * 3 * pidProfile->D8[axis] * PIDweight[axis] / 100) >> 8;
|
||||
|
||||
// -----calculate total PID output
|
||||
axisPID[axis] = PTerm + ITerm + DTerm;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue