mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 21:05:35 +03:00
Iterm reset only on yaw for now
This commit is contained in:
parent
7c83d23ddf
commit
24b97aed01
1 changed files with 8 additions and 4 deletions
|
@ -205,10 +205,12 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
||||||
// -----calculate I component.
|
// -----calculate I component.
|
||||||
errorGyroIf[axis] = constrainf(errorGyroIf[axis] + RateError * getdT() * pidProfile->I8[axis] / 10.0f, -250.0f, 250.0f);
|
errorGyroIf[axis] = constrainf(errorGyroIf[axis] + RateError * getdT() * pidProfile->I8[axis] / 10.0f, -250.0f, 250.0f);
|
||||||
|
|
||||||
|
if (IS_RC_MODE_ACTIVE(BOXSUPEREXPO) && axis != YAW) {
|
||||||
|
if (ABS(gyroRate) >= pidProfile->rollPitchItermResetRate) errorGyroIf[axis] = 0;
|
||||||
|
}
|
||||||
|
|
||||||
if (axis == YAW) {
|
if (axis == YAW) {
|
||||||
if (ABS(gyroRate) >= pidProfile->yawItermResetRate) errorGyroIf[axis] = 0;
|
if (ABS(gyroRate) >= pidProfile->yawItermResetRate) errorGyroIf[axis] = 0;
|
||||||
} else {
|
|
||||||
if (ABS(gyroRate) >= pidProfile->rollPitchItermResetRate) errorGyroIf[axis] = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (antiWindupProtection || motorLimitReached) {
|
if (antiWindupProtection || motorLimitReached) {
|
||||||
|
@ -490,10 +492,12 @@ static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *co
|
||||||
// I coefficient (I8) moved before integration to make limiting independent from PID settings
|
// I coefficient (I8) moved before integration to make limiting independent from PID settings
|
||||||
errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) - GYRO_I_MAX << 13, (int32_t) + GYRO_I_MAX << 13);
|
errorGyroI[axis] = constrain(errorGyroI[axis], (int32_t) - GYRO_I_MAX << 13, (int32_t) + GYRO_I_MAX << 13);
|
||||||
|
|
||||||
|
if (IS_RC_MODE_ACTIVE(BOXSUPEREXPO) && axis != YAW) {
|
||||||
|
if (ABS(gyroRate / 4) >= pidProfile->rollPitchItermResetRate) errorGyroI[axis] = 0;
|
||||||
|
}
|
||||||
|
|
||||||
if (axis == YAW) {
|
if (axis == YAW) {
|
||||||
if (ABS(gyroRate / 4) >= pidProfile->yawItermResetRate) errorGyroI[axis] = 0;
|
if (ABS(gyroRate / 4) >= pidProfile->yawItermResetRate) errorGyroI[axis] = 0;
|
||||||
} else {
|
|
||||||
if (ABS(gyroRate / 4) >= pidProfile->rollPitchItermResetRate) errorGyroI[axis] = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (antiWindupProtection || motorLimitReached) {
|
if (antiWindupProtection || motorLimitReached) {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue