1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 13:25:30 +03:00

Adjust Delta Scaling on MW23

This commit is contained in:
borisbstyle 2016-02-26 00:45:43 +01:00
parent 14bd2ccc7f
commit bc23418cec

View file

@ -361,7 +361,7 @@ static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *control
}
// Scale delta to looptime
delta = (delta * ((uint16_t) 0xFFFF)) / ((uint16_t)targetPidLooptime << 3);
delta = (delta * ((uint16_t) 0xFFFF)) / ((uint16_t)targetPidLooptime << 5);
if (deltaStateIsSet) {
DTerm = lrintf(applyBiQuadFilter((float) delta, &deltaBiQuadState[axis])) * 3; // Keep same scaling as unfiltered delta