1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-25 09:16:07 +03:00

Merge branch 'betaflight' of https://github.com/borisbstyle/betaflight into betaflight

This commit is contained in:
borisbstyle 2016-02-09 22:22:02 +01:00
commit 19d1a92c4f
2 changed files with 1 additions and 30 deletions

View file

@ -1807,35 +1807,6 @@ static void cliDump(char *cmdline)
cliPrint("\r\n# profile\r\n");
cliProfile("");
cliPrint("\r\n# aux\r\n");
cliAux("");
cliPrint("\r\n# adjrange\r\n");
cliAdjustmentRange("");
cliPrintf("\r\n# rxrange\r\n");
cliRxRange("");
#ifdef USE_SERVOS
cliPrint("\r\n# servo\r\n");
cliServo("");
// print servo directions
unsigned int channel;
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
if (servoDirection(i, channel) < 0) {
cliPrintf("smix reverse %d %d r\r\n", i , channel);
}
}
}
#endif
printSectionBreak();
dumpValues(PROFILE_VALUE);

View file

@ -219,7 +219,7 @@ void filterRc(void){
void scaleRcCommandToFpvCamAngle(void) {
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[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);
}