1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-13 19:40:31 +03:00

White space tidy

This commit is contained in:
jflyper 2020-02-15 14:59:11 +09:00 committed by mikeller
parent d25c852098
commit ff16686893
58 changed files with 310 additions and 310 deletions

View file

@ -652,7 +652,7 @@ void pidInitConfig(const pidProfile_t *pidProfile)
#endif
itermRotation = pidProfile->iterm_rotation;
antiGravityMode = pidProfile->antiGravityMode;
// Calculate the anti-gravity value that will trigger the OSD display.
// For classic AG it's either 1.0 for off and > 1.0 for on.
// For the new AG it's a continuous floating value so we want to trigger the OSD
@ -729,7 +729,7 @@ void pidInitConfig(const pidProfile_t *pidProfile)
thrustLinearizationReciprocal = 1.0f / thrustLinearization;
thrustLinearizationB = (1.0f - thrustLinearization) / (2.0f * thrustLinearization);
}
#endif
#endif
#if defined(USE_D_MIN)
for (int axis = FD_ROLL; axis <= FD_YAW; ++axis) {
const uint8_t dMin = pidProfile->d_min[axis];
@ -1004,7 +1004,7 @@ static FAST_CODE_NOINLINE float applyAcroTrainer(int axis, const rollAndPitchTri
if (acroTrainerAxisState[axis] != 0) {
ret = constrainf(((acroTrainerAngleLimit * angleSign) - currentAngle) * acroTrainerGain, -ACRO_TRAINER_SETPOINT_LIMIT, ACRO_TRAINER_SETPOINT_LIMIT);
} else {
// Not currently over the limit so project the angle based on current angle and
// gyro angular rate using a sliding window based on gyro rate (faster rotation means larger window.
// If the projected angle exceeds the limit then apply limiting to minimize overshoot.
@ -1021,7 +1021,7 @@ static FAST_CODE_NOINLINE float applyAcroTrainer(int axis, const rollAndPitchTri
if (resetIterm) {
pidData[axis].I = 0;
}
if (axis == acroTrainerDebugAxis) {
DEBUG_SET(DEBUG_ACRO_TRAINER, 0, lrintf(currentAngle * 10.0f));
DEBUG_SET(DEBUG_ACRO_TRAINER, 1, acroTrainerAxisState[axis]);
@ -1523,7 +1523,7 @@ void FAST_CODE pidController(const pidProfile_t *pidProfile, timeUs_t currentTim
if (yawSpinActive) {
pidData[axis].I = 0; // in yaw spin always disable I
if (axis <= FD_PITCH) {
// zero PIDs on pitch and roll leaving yaw P to correct spin
// zero PIDs on pitch and roll leaving yaw P to correct spin
pidData[axis].P = 0;
pidData[axis].D = 0;
pidData[axis].F = 0;