Index: PIDControllers.c =================================================================== diff -u -r0ead56df33c1583486ca3a8f8eeeeadfa5f11eb5 -raa6bdd3bfc3bd8bc1a56670c2bdadc32c99b33c3 --- PIDControllers.c (.../PIDControllers.c) (revision 0ead56df33c1583486ca3a8f8eeeeadfa5f11eb5) +++ PIDControllers.c (.../PIDControllers.c) (revision aa6bdd3bfc3bd8bc1a56670c2bdadc32c99b33c3) @@ -116,7 +116,7 @@ controller->uMin = controlMin; controller->uMax = controlMax; controller->isFeedForwardEnabled = isFeedForwardEnabled; - resetPIController( controllerID, initialControlSignal, feedFowardSignal ); + resetPIDController( controllerID, initialControlSignal, feedFowardSignal ); } else { @@ -294,47 +294,47 @@ switch( signalID ) { - case CONTROLLER_SIGNAL_REFERENCE: + case CONTROLLER_SIGNAL_PID_REFERENCE: output = controller->referenceSignal; break; - case CONTROLLER_SIGNAL_MEASURED: + case CONTROLLER_SIGNAL_PID_MEASURED: output = controller->measuredSignal; break; - case CONTROLLER_SIGNAL_ERROR: + case CONTROLLER_SIGNAL_PID_ERROR: output = controller->errorSignal; break; - case CONTROLLER_SIGNAL_ERROR_SUM: + case CONTROLLER_SIGNAL_PID_ERROR_SUM: output = controller->errorSumBeforeWindUp; break; - case CONTROLLER_SIGNAL_ERROR_SUM_AFTER_WINDUP: + case CONTROLLER_SIGNAL_PID_ERROR_SUM_AFTER_WINDUP: output = controller->errorSum; break; - case CONTROLLER_SIGNAL_PROPORTIONAL_OUTPUT: + case CONTROLLER_SIGNAL_PID_PROPORTIONAL_OUTPUT: output = controller->Kp * controller->errorSignal; break; - case CONTROLLER_SIGNAL_INTEGRAL_OUTPUT: + case CONTROLLER_SIGNAL_PID_INTEGRAL_OUTPUT: output = controller->Ki * controller->errorSum; break; - case CONTROLLER_SIGNAL_FEEDFORWARD_OUTPUT: + case CONTROLLER_SIGNAL_PID_FEEDFORWARD_OUTPUT: output = controller->feedForward; break; - case CONTROLLER_SIGNAL_CONTROL: + case CONTROLLER_SIGNAL_PID_CONTROL: output = controller->controlSignal; break; - case CONTROLLER_SIGNAL_ERROR_PREVIOUS: + case CONTROLLER_SIGNAL_PID_ERROR_PREVIOUS: output = controller->errorPrevious; break; - case CONTROLLER_SIGNAL_DERIVATIVE_OUTPUT: + case CONTROLLER_SIGNAL_PID_DERIVATIVE_OUTPUT: output = controller->Kd * ( controller->errorSignal - controller->errorPrevious ); default: