diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index b780f1a474..6f809f1f6a 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -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); diff --git a/src/main/mw.c b/src/main/mw.c index 3ba114b4a4..afd3c1efae 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -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); }