mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
merge upstream into sirinfpv branch
This commit is contained in:
commit
a147f15258
4 changed files with 15 additions and 3 deletions
|
@ -42,6 +42,7 @@ Cleanflight also has additional features not found in baseflight.
|
||||||
* Graupner HoTT telemetry.
|
* Graupner HoTT telemetry.
|
||||||
* Multiple simultaneous telemetry providers.
|
* Multiple simultaneous telemetry providers.
|
||||||
* Configurable serial ports for Serial RX, Telemetry, MSP, GPS - Use most devices on any port, softserial too.
|
* Configurable serial ports for Serial RX, Telemetry, MSP, GPS - Use most devices on any port, softserial too.
|
||||||
|
* Optional lost buzzer on port 6 for CC3D (set enable_buzzer_p6 = ON)
|
||||||
* And many more minor bug fixes.
|
* And many more minor bug fixes.
|
||||||
|
|
||||||
For a list of features, changes and some discussion please review the thread on MultiWii forums and consult the documentation.
|
For a list of features, changes and some discussion please review the thread on MultiWii forums and consult the documentation.
|
||||||
|
|
0
fake_travis_build.sh
Normal file → Executable file
0
fake_travis_build.sh
Normal file → Executable file
|
@ -188,7 +188,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
|
||||||
pidProfile->P_f[PITCH] = 1.4f;
|
pidProfile->P_f[PITCH] = 1.4f;
|
||||||
pidProfile->I_f[PITCH] = 0.4f;
|
pidProfile->I_f[PITCH] = 0.4f;
|
||||||
pidProfile->D_f[PITCH] = 0.01f;
|
pidProfile->D_f[PITCH] = 0.01f;
|
||||||
pidProfile->P_f[YAW] = 4.0f;
|
pidProfile->P_f[YAW] = 2.5f;
|
||||||
pidProfile->I_f[YAW] = 0.4f;
|
pidProfile->I_f[YAW] = 0.4f;
|
||||||
pidProfile->D_f[YAW] = 0.00f;
|
pidProfile->D_f[YAW] = 0.00f;
|
||||||
pidProfile->A_level = 4.0f;
|
pidProfile->A_level = 4.0f;
|
||||||
|
|
|
@ -205,10 +205,21 @@ void filterRc(void){
|
||||||
}
|
}
|
||||||
|
|
||||||
void scaleRcCommandToFpvCamAngle(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 roll = rcCommand[ROLL];
|
||||||
int16_t yaw = rcCommand[YAW];
|
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(roll * cosFactor - yaw * sinFactor, -500, 500);
|
||||||
rcCommand[YAW] = constrain(cos(masterConfig.rxConfig.fpvCamAngleDegrees*RAD) * yaw + sin(masterConfig.rxConfig.fpvCamAngleDegrees*RAD) * roll, -500, 500);
|
rcCommand[YAW] = constrain(yaw * cosFactor + roll * sinFactor, -500, 500);
|
||||||
}
|
}
|
||||||
|
|
||||||
void annexCode(void)
|
void annexCode(void)
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue