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

Apply PID reduction to only Iterm. (RC1 behaviour)

This commit is contained in:
borisbstyle 2016-06-19 15:21:26 +02:00
parent 8353659c73
commit 9782fb1555
2 changed files with 9 additions and 7 deletions

View file

@ -825,7 +825,7 @@ void mixTable(void)
rollPitchYawMix[i] = qMultiply(mixReduction,rollPitchYawMix[i]); rollPitchYawMix[i] = qMultiply(mixReduction,rollPitchYawMix[i]);
} }
// Get the maximum correction by setting offset to center // Get the maximum correction by setting offset to center
throttleMin = throttleMax = throttleMin + (throttleRange / 2); if (!escAndServoConfig->escDesyncProtection) throttleMin = throttleMax = throttleMin + (throttleRange / 2);
} else { } else {
throttleMin = throttleMin + (rollPitchYawMixRange / 2); throttleMin = throttleMin + (rollPitchYawMixRange / 2);
throttleMax = throttleMax - (rollPitchYawMixRange / 2); throttleMax = throttleMax - (rollPitchYawMixRange / 2);

View file

@ -174,13 +174,13 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, uint16_t max_angle_incli
// Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes // Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes
// -----calculate scaled error.AngleRates // -----calculate scaled error.AngleRates
// multiplication of rcCommand corresponds to changing the sticks scaling here // multiplication of rcCommand corresponds to changing the sticks scaling here
RateError = (angleRate[axis] - gyroRate) * errorLimiter; RateError = angleRate[axis] - gyroRate;
// Smoothed Error for Derivative // Smoothed Error for Derivative
if (flightModeFlags && axis != YAW) { if (flightModeFlags && axis != YAW) {
RateErrorSmooth = RateError; RateErrorSmooth = RateError;
} else { } else {
RateErrorSmooth = (angleRateSmooth[axis] - gyroRate) * errorLimiter; RateErrorSmooth = angleRateSmooth[axis] - gyroRate;
} }
// -----calculate P component // -----calculate P component
@ -194,7 +194,7 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, uint16_t max_angle_incli
// -----calculate I component. // -----calculate I component.
uint16_t kI = (pidProfile->dynamic_pid) ? getDynamicKi(axis, pidProfile, (int32_t)angleRate[axis]) : pidProfile->I8[axis]; uint16_t kI = (pidProfile->dynamic_pid) ? getDynamicKi(axis, pidProfile, (int32_t)angleRate[axis]) : pidProfile->I8[axis];
errorGyroIf[axis] = constrainf(errorGyroIf[axis] + luxITermScale * RateError * getdT() * kI, -250.0f, 250.0f); errorGyroIf[axis] = constrainf(errorGyroIf[axis] + luxITermScale * errorLimiter * RateError * getdT() * kI, -250.0f, 250.0f);
// limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated. // limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated.
// 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
@ -299,13 +299,13 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, uint16_t max_angl
// multiplication of rcCommand corresponds to changing the sticks scaling here // multiplication of rcCommand corresponds to changing the sticks scaling here
gyroRate = gyroADC[axis] / 4; gyroRate = gyroADC[axis] / 4;
RateError = (AngleRateTmp - gyroRate) * errorLimiter; RateError = AngleRateTmp - gyroRate;
// Smoothed Error for Derivative // Smoothed Error for Derivative
if (flightModeFlags && axis != YAW) { if (flightModeFlags && axis != YAW) {
RateErrorSmooth = RateError; RateErrorSmooth = RateError;
} else { } else {
RateErrorSmooth = (AngleRateTmpSmooth - gyroRate) * errorLimiter; RateErrorSmooth = AngleRateTmpSmooth - gyroRate;
} }
// -----calculate P component // -----calculate P component
@ -323,7 +323,9 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, uint16_t max_angl
// is normalized to cycle time = 2048. // is normalized to cycle time = 2048.
uint16_t kI = (pidProfile->dynamic_pid) ? getDynamicKi(axis, pidProfile, AngleRateTmp) : pidProfile->I8[axis]; uint16_t kI = (pidProfile->dynamic_pid) ? getDynamicKi(axis, pidProfile, AngleRateTmp) : pidProfile->I8[axis];
errorGyroI[axis] = errorGyroI[axis] + ((RateError * (uint16_t)targetPidLooptime) >> 11) * kI; int32_t rateErrorLimited = errorLimiter * RateError;
errorGyroI[axis] = errorGyroI[axis] + ((rateErrorLimited * (uint16_t)targetPidLooptime) >> 11) * kI;
// limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated. // limit maximum integrator value to prevent WindUp - accumulating extreme values when system is saturated.
// 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