1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 00:05:33 +03:00

Rename some PID controller methods.

See #461.
This commit is contained in:
Dominic Clifton 2015-03-09 23:26:52 +00:00
parent d8cd9f239c
commit bc8e53a9d8
5 changed files with 12 additions and 13 deletions

View file

@ -520,8 +520,8 @@ void processRx(void)
throttleStatus_e throttleStatus = calculateThrottleStatus(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
if (throttleStatus == THROTTLE_LOW) {
resetErrorAngle();
resetErrorGyro();
pidResetErrorAngle();
pidResetErrorGyro();
}
// When armed and motors aren't spinning, disarm board after delay so users without buzzer won't lose fingers.
// mixTable constrains motor commands, so checking throttleStatus is enough
@ -557,7 +557,7 @@ void processRx(void)
canUseHorizonMode = false;
if (!FLIGHT_MODE(ANGLE_MODE)) {
resetErrorAngle();
pidResetErrorAngle();
ENABLE_FLIGHT_MODE(ANGLE_MODE);
}
} else {
@ -569,7 +569,7 @@ void processRx(void)
DISABLE_FLIGHT_MODE(ANGLE_MODE);
if (!FLIGHT_MODE(HORIZON_MODE)) {
resetErrorAngle();
pidResetErrorAngle();
ENABLE_FLIGHT_MODE(HORIZON_MODE);
}
} else {