diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 42cfe7f9cb..d123250484 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -523,13 +523,10 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) UNUSED(rxConfig); float delta, RCfactor, rcCommandAxis, MainDptCut, gyroDataQuant; - float PTerm = 0.0f, ITerm = 0.0f, DTerm = 0.0f, PTermACC = 0.0f, ITermACC = 0.0f, ITermGYRO = 0.0f, error = 0.0f, prop = 0.0f; + float PTerm, ITerm, DTerm, PTermACC = 0.0f, ITermACC = 0.0f, ITermGYRO, error, prop = 0.0f; static float lastGyro[2] = { 0.0f, 0.0f }, lastDTerm[2] = { 0.0f, 0.0f }; - float tmp0flt; - int32_t tmp0; uint8_t axis; - float ACCDeltaTimeINS = 0.0f; - float FLOATcycleTime = 0.0f; + float ACCDeltaTimeINS, FLOATcycleTime, Mwii3msTimescale; // MainDptCut = RCconstPI / (float)cfg.maincuthz; // Initialize Cut off frequencies for mainpid D MainDptCut = RCconstPI / MAIN_CUT_HZ; // maincuthz (default 12Hz, Range 1-50Hz), hardcoded for now @@ -542,8 +539,8 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) } for (axis = 0; axis < 2; axis++) { - tmp0 = (int32_t)((float)gyroData[axis] * 0.3125f); // Multiwii masks out the last 2 bits, this has the same idea - gyroDataQuant = (float)tmp0 * 3.2f; // but delivers more accuracy and also reduces jittery flight + int32_t tmp = (int32_t)((float)gyroData[axis] * 0.3125f); // Multiwii masks out the last 2 bits, this has the same idea + gyroDataQuant = (float)tmp * 3.2f; // but delivers more accuracy and also reduces jittery flight rcCommandAxis = (float)rcCommand[axis]; // Calculate common values for pid controllers if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { #ifdef GPS @@ -558,8 +555,8 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) } #endif PTermACC = error * (float)pidProfile->P8[PIDLEVEL] * 0.008f; - tmp0flt = (float)pidProfile->D8[PIDLEVEL] * 5.0f; - PTermACC = constrain(PTermACC, -tmp0flt, +tmp0flt); + float limitf = (float)pidProfile->D8[PIDLEVEL] * 5.0f; + PTermACC = constrain(PTermACC, -limitf, +limitf); errorAngleIf[axis] = constrain(errorAngleIf[axis] + error * ACCDeltaTimeINS, -30.0f, +30.0f); ITermACC = errorAngleIf[axis] * (float)pidProfile->I8[PIDLEVEL] * 0.08f; } @@ -602,37 +599,37 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) #endif } - tmp0flt = (int32_t)FLOATcycleTime & (int32_t)~3; // Filter last 2 bit jitter - tmp0flt /= 3000.0f; + Mwii3msTimescale = (int32_t)FLOATcycleTime & (int32_t)~3; // Filter last 2 bit jitter + Mwii3msTimescale /= 3000.0f; if (OLD_YAW) { // [0/1] 0 = multiwii 2.3 yaw, 1 = older yaw. hardcoded for now PTerm = ((int32_t)pidProfile->P8[FD_YAW] * (100 - (int32_t)controlRateConfig->yawRate * (int32_t)ABS(rcCommand[FD_YAW]) / 500)) / 100; - tmp0 = lrintf(gyroData[FD_YAW] * 0.25f); - PTerm = rcCommand[FD_YAW] - tmp0 * PTerm / 80; - if ((ABS(tmp0) > 640) || (ABS(rcCommand[FD_YAW]) > 100)) { + int32_t tmp = lrintf(gyroData[FD_YAW] * 0.25f); + PTerm = rcCommand[FD_YAW] - tmp * PTerm / 80; + if ((ABS(tmp) > 640) || (ABS(rcCommand[FD_YAW]) > 100)) { errorGyroI[FD_YAW] = 0; } else { - error = ((int32_t)rcCommand[FD_YAW] * 80 / (int32_t)pidProfile->P8[FD_YAW]) - tmp0; - errorGyroI[FD_YAW] = constrain(errorGyroI[FD_YAW] + (int32_t)(error * tmp0flt), -16000, +16000); // WindUp + error = ((int32_t)rcCommand[FD_YAW] * 80 / (int32_t)pidProfile->P8[FD_YAW]) - tmp; + errorGyroI[FD_YAW] = constrain(errorGyroI[FD_YAW] + (int32_t)(error * Mwii3msTimescale), -16000, +16000); // WindUp ITerm = (errorGyroI[FD_YAW] / 125 * pidProfile->I8[FD_YAW]) >> 6; } } else { - tmp0 = ((int32_t)rcCommand[FD_YAW] * (((int32_t)controlRateConfig->yawRate << 1) + 40)) >> 5; - error = tmp0 - lrintf(gyroData[FD_YAW] * 0.25f); // Less Gyrojitter works actually better + int32_t tmp = ((int32_t)rcCommand[FD_YAW] * (((int32_t)controlRateConfig->yawRate << 1) + 40)) >> 5; + error = tmp - lrintf(gyroData[FD_YAW] * 0.25f); // Less Gyrojitter works actually better - if (ABS(tmp0) > 50) { + if (ABS(tmp) > 50) { errorGyroI[FD_YAW] = 0; } else { - errorGyroI[FD_YAW] = constrain(errorGyroI[FD_YAW] + (int32_t)(error * (float)pidProfile->I8[FD_YAW] * tmp0flt), -268435454, +268435454); + errorGyroI[FD_YAW] = constrain(errorGyroI[FD_YAW] + (int32_t)(error * (float)pidProfile->I8[FD_YAW] * Mwii3msTimescale), -268435454, +268435454); } ITerm = constrain(errorGyroI[FD_YAW] >> 13, -GYRO_I_MAX, +GYRO_I_MAX); PTerm = ((int32_t)error * (int32_t)pidProfile->P8[FD_YAW]) >> 6; if (motorCount >= 4) { // Constrain FD_YAW by D value if not servo driven in that case servolimits apply - tmp0 = 300; - if (pidProfile->D8[FD_YAW]) tmp0 -= (int32_t)pidProfile->D8[FD_YAW]; - PTerm = constrain(PTerm, -tmp0, tmp0); + int32_t limit = 300; + if (pidProfile->D8[FD_YAW]) limit -= (int32_t)pidProfile->D8[FD_YAW]; + PTerm = constrain(PTerm, -limit, limit); } } axisPID[FD_YAW] = PTerm + ITerm;