1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 22:35:23 +03:00

Change D Scale to match CF transition better

This commit is contained in:
borisbstyle 2015-12-02 21:56:32 +01:00
parent 5f1540dbcb
commit 769ddd39af
2 changed files with 5 additions and 5 deletions

View file

@ -318,7 +318,7 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat
delta = filterApplyPt1(delta, &DTermState[axis], pidProfile->dterm_cut_hz, dT);
}
DTerm = (delta * 3 * pidProfile->D8[axis] * PIDweight[axis] / 100) >> 8; // Multiplied by 3 to match old scaling
DTerm = (delta * 2 * pidProfile->D8[axis] * PIDweight[axis] / 100) >> 8; // Multiplied by 2 to approximately match old scaling
// -----calculate total PID output
axisPID[axis] = PTerm + ITerm + DTerm;