mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
yaw improvement
this should stop the copter from carrying on spinning at high yaw rates. Conflicts: src/mw.c
This commit is contained in:
parent
d6545efa10
commit
432c43bab7
1 changed files with 3 additions and 2 deletions
|
@ -194,8 +194,9 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
||||||
PTermGYRO = rcCommand[axis];
|
PTermGYRO = rcCommand[axis];
|
||||||
|
|
||||||
errorGyroI[axis] = constrain(errorGyroI[axis] + error, -16000, +16000); // WindUp
|
errorGyroI[axis] = constrain(errorGyroI[axis] + error, -16000, +16000); // WindUp
|
||||||
if (abs(gyroData[axis]) > (640 * 4))
|
if ((abs(gyroData[axis]) > 640) || (abs(rcCommand[axis]) > 50))
|
||||||
errorGyroI[axis] = 0;
|
errorGyroI[axis] = 0;
|
||||||
|
|
||||||
ITermGYRO = (errorGyroI[axis] / 125 * pidProfile->I8[axis]) / 64;
|
ITermGYRO = (errorGyroI[axis] / 125 * pidProfile->I8[axis]) / 64;
|
||||||
}
|
}
|
||||||
if (f.HORIZON_MODE && (axis == FD_ROLL || axis == FD_PITCH)) {
|
if (f.HORIZON_MODE && (axis == FD_ROLL || axis == FD_PITCH)) {
|
||||||
|
@ -239,7 +240,7 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat
|
||||||
for (axis = 0; axis < 3; axis++) {
|
for (axis = 0; axis < 3; axis++) {
|
||||||
// -----Get the desired angle rate depending on flight mode
|
// -----Get the desired angle rate depending on flight mode
|
||||||
if (axis == FD_YAW) { // YAW is always gyro-controlled (MAG correction is applied to rcCommand)
|
if (axis == FD_YAW) { // YAW is always gyro-controlled (MAG correction is applied to rcCommand)
|
||||||
AngleRateTmp = (((int32_t)(controlRateConfig->yawRate + 27) * rcCommand[2]) >> 5);
|
AngleRateTmp = (((int32_t)(controlRateConfig->yawRate + 27) * rcCommand[YAW]) >> 5);
|
||||||
} else {
|
} else {
|
||||||
// calculate error and limit the angle to max configured inclination
|
// calculate error and limit the angle to max configured inclination
|
||||||
errorAngle = constrain((rcCommand[axis] << 1) + GPS_angle[axis], -((int) max_angle_inclination),
|
errorAngle = constrain((rcCommand[axis] << 1) + GPS_angle[axis], -((int) max_angle_inclination),
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue