diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 044289ee0..3809062c1 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -59,7 +59,7 @@ int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; #endif // PIDweight is a scale factor for PIDs which is derived from the throttle and TPA setting, and 100 = 100% scale means no PID reduction -uint8_t dynP8[3], dynI8[3], dynD8[3], PIDweight[3]; +uint8_t PIDweight[3]; static int32_t errorGyroI[3], errorGyroILimit[3]; static float errorGyroIf[3], errorGyroIfLimit[3]; @@ -273,145 +273,6 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa } } -static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination, - rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) -{ - UNUSED(rxConfig); - - int axis, prop = 0; - int32_t rc, error, errorAngle, delta, gyroError; - int32_t PTerm, ITerm, PTermACC, ITermACC, DTerm; - static int16_t lastErrorForDelta[2]; - static int32_t deltaState[3][DELTA_MAX_SAMPLES]; - - if (FLIGHT_MODE(HORIZON_MODE)) { - prop = MIN(MAX(ABS(rcCommand[PITCH]), ABS(rcCommand[ROLL])), 512); - } - - // PITCH & ROLL - for (axis = 0; axis < 2; axis++) { - - rc = rcCommand[axis] << 1; - - gyroError = gyroADC[axis] / 4; - - error = rc - gyroError; - 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; - } - - // Anti windup protection - if (antiWindupProtection || motorLimitReached) { - errorGyroI[axis] = constrain(errorGyroI[axis], -errorGyroILimit[axis], errorGyroILimit[axis]); - } else { - errorGyroILimit[axis] = ABS(errorGyroI[axis]); - } - - ITerm = (errorGyroI[axis] >> 7) * pidProfile->I8[axis] >> 6; // 16 bits is ok here 16000/125 = 128 ; 128*250 = 32000 - - PTerm = (int32_t)rc * pidProfile->P8[axis] >> 6; - - if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { // axis relying on ACC - // 50 degrees max inclination -#ifdef GPS - errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination), - +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]; -#else - errorAngle = constrain(2 * rcCommand[axis], -((int) max_angle_inclination), - +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]; -#endif - - errorAngleI[axis] = constrain(errorAngleI[axis] + errorAngle, -10000, +10000); // WindUp //16 bits is ok here - - PTermACC = ((int32_t)errorAngle * pidProfile->P8[PIDLEVEL]) >> 7; // 32 bits is needed for calculation: errorAngle*P8 could exceed 32768 16 bits is ok for result - - int16_t limit = pidProfile->D8[PIDLEVEL] * 5; - PTermACC = constrain(PTermACC, -limit, +limit); - - ITermACC = ((int32_t)errorAngleI[axis] * pidProfile->I8[PIDLEVEL]) >> 12; // 32 bits is needed for calculation:10000*I8 could exceed 32768 16 bits is ok for result - - ITerm = ITermACC + ((ITerm - ITermACC) * prop >> 9); - PTerm = PTermACC + ((PTerm - PTermACC) * prop >> 9); - } - - PTerm -= ((int32_t)gyroError * dynP8[axis]) >> 6; // 32 bits is needed for calculation - - //-----calculate D-term based on the configured approach (delta from measurement or deltafromError) - if (pidProfile->deltaMethod == DELTA_FROM_ERROR) { - delta = error - lastErrorForDelta[axis]; - lastErrorForDelta[axis] = error; - } else { /* Delta from measurement */ - delta = -(gyroError - lastErrorForDelta[axis]); - lastErrorForDelta[axis] = gyroError; - } - - // Scale delta to looptime - delta = (delta * ((uint16_t) 0xFFFF)) / ((uint16_t)targetPidLooptime << 5); - - // Filer delta - if (pidProfile->dterm_lpf_hz) delta = filterApplyPt1((float)delta, &deltaFilterState[axis], pidProfile->dterm_lpf_hz, getdT()); - - // Apply moving average and multiply to get original scaling - if (pidProfile->dterm_average_count) delta = filterApplyAverage(delta, pidProfile->dterm_average_count, deltaState[axis]) * 2; - - DTerm = (delta * dynD8[axis]) >> 5; // 32 bits is needed for calculation - - axisPID[axis] = PTerm + ITerm + DTerm; - - if (lowThrottlePidReduction) axisPID[axis] /= 3; - -#ifdef GTUNE - if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { - calculate_Gtune(axis); - } -#endif - -#ifdef BLACKBOX - axisPID_P[axis] = PTerm; - axisPID_I[axis] = ITerm; - axisPID_D[axis] = DTerm; -#endif - } - - //YAW - rc = (int32_t)rcCommand[FD_YAW] * (2 * controlRateConfig->rates[FD_YAW] + 30) >> 5; -#ifdef ALIENWII32 - error = rc - gyroADC[FD_YAW]; -#else - error = rc - (gyroADC[FD_YAW] / 4); -#endif - errorGyroI[FD_YAW] += (int32_t)error * pidProfile->I8[FD_YAW]; - errorGyroI[FD_YAW] = constrain(errorGyroI[FD_YAW], 2 - ((int32_t)1 << 28), -2 + ((int32_t)1 << 28)); - if (ABS(rc) > 50) errorGyroI[FD_YAW] = 0; - - PTerm = (int32_t)error * pidProfile->P8[FD_YAW] >> 6; // TODO: Bitwise shift on a signed integer is not recommended - - // Constrain YAW by yaw_p_limit value if not servo driven in that case servolimits apply - if(motorCount >= 4 && pidProfile->yaw_p_limit < YAW_P_LIMIT_MAX) { - PTerm = constrain(PTerm, -pidProfile->yaw_p_limit, pidProfile->yaw_p_limit); - } - - ITerm = constrain((int16_t)(errorGyroI[FD_YAW] >> 13), -GYRO_I_MAX, +GYRO_I_MAX); - - axisPID[FD_YAW] = PTerm + ITerm; - - if (pidProfile->yaw_lpf_hz) axisPID[FD_YAW] = filterApplyPt1(axisPID[FD_YAW], &yawFilterState, pidProfile->yaw_lpf_hz, getdT()); - -#ifdef GTUNE - if (FLIGHT_MODE(GTUNE_MODE) && ARMING_FLAG(ARMED)) { - calculate_Gtune(FD_YAW); - } -#endif - -#ifdef BLACKBOX - axisPID_P[FD_YAW] = PTerm; - axisPID_I[FD_YAW] = ITerm; - axisPID_D[FD_YAW] = 0; -#endif -} - static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig) { @@ -567,9 +428,6 @@ void pidSetController(pidControllerType_e type) break; case PID_CONTROLLER_LUX_FLOAT: pid_controller = pidLuxFloat; - break; - case PID_CONTROLLER_MW23: - pid_controller = pidMultiWii23; } } diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 4208ad6c4..dfcce336f 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -37,8 +37,7 @@ typedef enum { } pidIndex_e; typedef enum { - PID_CONTROLLER_MW23, - PID_CONTROLLER_MWREWRITE, + PID_CONTROLLER_MWREWRITE = 1, PID_CONTROLLER_LUX_FLOAT, PID_COUNT } pidControllerType_e; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 7106a99fb..b2f19e1c8 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -371,7 +371,7 @@ static const char * const lookupTableBlackboxDevice[] = { static const char * const lookupTablePidController[] = { - "MW23", "MWREWRITE", "LUX" + "UNUSED", "MWREWRITE", "LUX" }; static const char * const lookupTableSerialRX[] = { diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 3561b2016..c78212430 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -1309,7 +1309,7 @@ static bool processInCommand(void) break; case MSP_SET_PID_CONTROLLER: oldPid = currentProfile->pidProfile.pidController; - currentProfile->pidProfile.pidController = read8(); + currentProfile->pidProfile.pidController = constrain(read8(), 1, 2); pidSetController(currentProfile->pidProfile.pidController); if (oldPid != currentProfile->pidProfile.pidController) setGyroSamplingSpeed(0); // recalculate looptimes for new PID break; diff --git a/src/main/mw.c b/src/main/mw.c index 11149dc04..7f7497f6b 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -223,16 +223,16 @@ void scaleRcCommandToFpvCamAngle(void) { void annexCode(void) { int32_t tmp, tmp2; - int32_t axis, prop1 = 0, prop2; + int32_t axis, prop; // PITCH & ROLL only dynamic PID adjustment, depending on throttle value if (rcData[THROTTLE] < currentControlRateProfile->tpa_breakpoint) { - prop2 = 100; + prop = 100; } else { if (rcData[THROTTLE] < 2000) { - prop2 = 100 - (uint16_t)currentControlRateProfile->dynThrPID * (rcData[THROTTLE] - currentControlRateProfile->tpa_breakpoint) / (2000 - currentControlRateProfile->tpa_breakpoint); + prop = 100 - (uint16_t)currentControlRateProfile->dynThrPID * (rcData[THROTTLE] - currentControlRateProfile->tpa_breakpoint) / (2000 - currentControlRateProfile->tpa_breakpoint); } else { - prop2 = 100 - currentControlRateProfile->dynThrPID; + prop = 100 - currentControlRateProfile->dynThrPID; } } @@ -249,8 +249,6 @@ void annexCode(void) tmp2 = tmp / 100; rcCommand[axis] = lookupPitchRollRC[tmp2] + (tmp - tmp2 * 100) * (lookupPitchRollRC[tmp2 + 1] - lookupPitchRollRC[tmp2]) / 100; - prop1 = 100 - (uint16_t)currentControlRateProfile->rates[axis] * tmp / 500; - prop1 = (uint16_t)prop1 * prop2 / 100; } else if (axis == YAW) { if (masterConfig.rcControlsConfig.yaw_deadband) { if (tmp > masterConfig.rcControlsConfig.yaw_deadband) { @@ -261,19 +259,14 @@ void annexCode(void) } tmp2 = tmp / 100; rcCommand[axis] = (lookupYawRC[tmp2] + (tmp - tmp2 * 100) * (lookupYawRC[tmp2 + 1] - lookupYawRC[tmp2]) / 100) * -masterConfig.yaw_control_direction; - prop1 = 100 - (uint16_t)currentControlRateProfile->rates[axis] * ABS(tmp) / 500; } - // FIXME axis indexes into pids. use something like lookupPidIndex(rc_alias_e alias) to reduce coupling. - dynP8[axis] = (uint16_t)currentProfile->pidProfile.P8[axis] * prop1 / 100; - dynI8[axis] = (uint16_t)currentProfile->pidProfile.I8[axis] * prop1 / 100; - dynD8[axis] = (uint16_t)currentProfile->pidProfile.D8[axis] * prop1 / 100; // non coupled PID reduction scaler used in PID controller 1 and PID controller 2. YAW TPA disabled. 100 means 100% of the pids if (axis == YAW) { PIDweight[axis] = 100; } else { - PIDweight[axis] = prop2; + PIDweight[axis] = prop; } if (rcData[axis] < masterConfig.rxConfig.midrc)