1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 21:35:44 +03:00

Iterm range for MW23 more sensitive

This commit is contained in:
borisbstyle 2016-03-21 00:08:10 +01:00
parent 087e3ae0f4
commit adedc3fe81

View file

@ -311,7 +311,7 @@ static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *control
gyroError = gyroADC[axis] / 4;
error = rc - gyroError;
errorGyroI[axis] = constrain(errorGyroI[axis] + ((error * (uint16_t)targetPidLooptime) >> 12) , -16000, +16000); // WindUp 16 bits is ok here
errorGyroI[axis] = constrain(errorGyroI[axis] + ((error * (uint16_t)targetPidLooptime) >> 11) , -16000, +16000); // WindUp 16 bits is ok here
if (ABS(gyroADC[axis]) > (640 * 4)) {
errorGyroI[axis] = 0;