mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 21:35:44 +03:00
Reduce low throttle response in normal mode
This commit is contained in:
parent
2dc424d83b
commit
9b43dfde19
1 changed files with 6 additions and 0 deletions
|
@ -203,6 +203,8 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
||||||
// multiplication of rcCommand corresponds to changing the sticks scaling here
|
// multiplication of rcCommand corresponds to changing the sticks scaling here
|
||||||
RateError = AngleRate - gyroRate;
|
RateError = AngleRate - gyroRate;
|
||||||
|
|
||||||
|
if (lowThrottlePidReduction) RateError /= 4;
|
||||||
|
|
||||||
// -----calculate P component
|
// -----calculate P component
|
||||||
PTerm = RateError * pidProfile->P_f[axis] * PIDweight[axis] / 100;
|
PTerm = RateError * pidProfile->P_f[axis] * PIDweight[axis] / 100;
|
||||||
|
|
||||||
|
@ -286,6 +288,8 @@ static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *control
|
||||||
|
|
||||||
rc = rcCommand[axis] << 1;
|
rc = rcCommand[axis] << 1;
|
||||||
|
|
||||||
|
if (lowThrottlePidReduction) rc /= 4;
|
||||||
|
|
||||||
gyroError = gyroADC[axis] / 4;
|
gyroError = gyroADC[axis] / 4;
|
||||||
|
|
||||||
error = rc - gyroError;
|
error = rc - gyroError;
|
||||||
|
@ -466,6 +470,8 @@ static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *co
|
||||||
gyroRate = gyroADC[axis] / 4;
|
gyroRate = gyroADC[axis] / 4;
|
||||||
RateError = AngleRateTmp - gyroRate;
|
RateError = AngleRateTmp - gyroRate;
|
||||||
|
|
||||||
|
if (lowThrottlePidReduction) RateError /= 4;
|
||||||
|
|
||||||
// -----calculate P component
|
// -----calculate P component
|
||||||
PTerm = (RateError * pidProfile->P8[axis] * PIDweight[axis] / 100) >> 7;
|
PTerm = (RateError * pidProfile->P8[axis] * PIDweight[axis] / 100) >> 7;
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue