1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 16:25:31 +03:00

Adjust i-term yaw zeroing.

See fe5a864 and b9e5a37.
This commit is contained in:
Dominic Clifton 2014-07-26 21:26:04 +01:00
parent 5086b46f1f
commit a39ae9929d

View file

@ -194,7 +194,7 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
PTermGYRO = rcCommand[axis]; PTermGYRO = rcCommand[axis];
errorGyroI[axis] = constrain(errorGyroI[axis] + error, -16000, +16000); // WindUp errorGyroI[axis] = constrain(errorGyroI[axis] + error, -16000, +16000); // WindUp
if ((abs(gyroData[axis]) > (640 * 4)) || (axis == FD_YAW && abs(rcCommand[axis]) > 50)) if ((abs(gyroData[axis]) > (640 * 4)) || (axis == FD_YAW && abs(rcCommand[axis]) > 100))
errorGyroI[axis] = 0; errorGyroI[axis] = 0;
ITermGYRO = (errorGyroI[axis] / 125 * pidProfile->I8[axis]) / 64; ITermGYRO = (errorGyroI[axis] / 125 * pidProfile->I8[axis]) / 64;