diff --git a/src/main/mw.c b/src/main/mw.c index e779c4542..1edd6441e 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -204,10 +204,21 @@ void filterRc(void){ } void scaleRcCommandToFpvCamAngle(void) { + //recalculate sin/cos only when masterConfig.rxConfig.fpvCamAngleDegrees changed + static uint8_t lastFpvCamAngleDegrees = 0; + static float cosFactor = 1.0; + static float sinFactor = 0.0; + + if (lastFpvCamAngleDegrees != masterConfig.rxConfig.fpvCamAngleDegrees){ + lastFpvCamAngleDegrees = masterConfig.rxConfig.fpvCamAngleDegrees; + cosFactor = cos_approx(masterConfig.rxConfig.fpvCamAngleDegrees * RAD); + sinFactor = sin_approx(masterConfig.rxConfig.fpvCamAngleDegrees * RAD); + } + int16_t roll = rcCommand[ROLL]; int16_t yaw = rcCommand[YAW]; - rcCommand[ROLL] = constrain(cos(masterConfig.rxConfig.fpvCamAngleDegrees*RAD) * roll - sin(masterConfig.rxConfig.fpvCamAngleDegrees*RAD) * yaw, -500, 500); - rcCommand[YAW] = constrain(cos(masterConfig.rxConfig.fpvCamAngleDegrees*RAD) * yaw + sin(masterConfig.rxConfig.fpvCamAngleDegrees*RAD) * roll, -500, 500); + rcCommand[ROLL] = constrain(roll * cosFactor - yaw * sinFactor, -500, 500); + rcCommand[YAW] = constrain(yaw * cosFactor + roll * sinFactor, -500, 500); } void annexCode(void)