From 20b7a9fbfb86760b21644aee61b52bf10e842f91 Mon Sep 17 00:00:00 2001 From: luggi Date: Sat, 7 Jun 2014 15:32:08 +0200 Subject: [PATCH] yaw improvement this should stop the copter from carrying on spinning at high yaw rates. --- src/mw.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/mw.c b/src/mw.c index 32197bae2..4c7323598 100755 --- a/src/mw.c +++ b/src/mw.c @@ -326,7 +326,7 @@ static void pidMultiWii(void) PTermGYRO = rcCommand[axis]; errorGyroI[axis] = constrain(errorGyroI[axis] + error, -16000, +16000); // WindUp - if (abs(gyroData[axis]) > 640) + if ((abs(gyroData[axis]) > 640) || (abs(rcCommand[axis]) > 50)) errorGyroI[axis] = 0; ITermGYRO = (errorGyroI[axis] / 125 * cfg.I8[axis]) >> 6; } @@ -370,7 +370,7 @@ static void pidRewrite(void) for (axis = 0; axis < 3; axis++) { // -----Get the desired angle rate depending on flight mode if (axis == 2) { // YAW is always gyro-controlled (MAG correction is applied to rcCommand) - AngleRateTmp = (((int32_t)(cfg.yawRate + 27) * rcCommand[2]) >> 5); + AngleRateTmp = (((int32_t)(cfg.yawRate + 27) * rcCommand[YAW]) >> 5); } else { // calculate error and limit the angle to 50 degrees max inclination errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -500, +500) - angle[axis] + cfg.angleTrim[axis]) / 10.0f; // 16 bits is ok here