Merge pull request #294 from rav-rav/camMix
improved speed of scaleRcCommandToFpvCamAngle
This commit is contained in:
commit
b7af576eb6
|
@ -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)
|
||||
|
|
Loading…
Reference in New Issue