1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-21 07:15:18 +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

@ -73,7 +73,6 @@
#define BRUSHED_MOTORS_PWM_RATE 16000
#define BRUSHLESS_MOTORS_PWM_RATE 400
void setPIDController(int type); // FIXME PID code needs to be in flight_pid.c/h
void mixerUseConfigs(
#ifdef USE_SERVOS
servoParam_t *servoConfToUse,
@ -636,7 +635,7 @@ void activateConfig(void)
useTelemetryConfig(&masterConfig.telemetryConfig);
#endif
setPIDController(currentProfile->pidProfile.pidController);
pidSetController(currentProfile->pidProfile.pidController);
#ifdef GPS
gpsUseProfile(&currentProfile->gpsProfile);

View file

@ -70,7 +70,7 @@ typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig
pidControllerFuncPtr pid_controller = pidMultiWii; // which pid controller are we using, defaultMultiWii
void resetErrorAngle(void)
void pidResetErrorAngle(void)
{
errorAngleI[ROLL] = 0;
errorAngleI[PITCH] = 0;
@ -79,7 +79,7 @@ void resetErrorAngle(void)
errorAngleIf[PITCH] = 0.0f;
}
void resetErrorGyro(void)
void pidResetErrorGyro(void)
{
errorGyroI[ROLL] = 0;
errorGyroI[PITCH] = 0;
@ -742,7 +742,7 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat
}
}
void setPIDController(int type)
void pidSetController(int type)
{
switch (type) {
case 0:

View file

@ -55,8 +55,8 @@ typedef struct pidProfile_s {
extern int16_t axisPID[XYZ_AXIS_COUNT];
extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
void setPIDController(int type);
void resetErrorAngle(void);
void resetErrorGyro(void);
void pidSetController(int type);
void pidResetErrorAngle(void);
void pidResetErrorGyro(void);

View file

@ -1257,7 +1257,7 @@ static bool processInCommand(void)
break;
case MSP_SET_PID_CONTROLLER:
currentProfile->pidProfile.pidController = read8();
setPIDController(currentProfile->pidProfile.pidController);
pidSetController(currentProfile->pidProfile.pidController);
break;
case MSP_SET_PID:
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) {

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 {