![]() |
Autonomy Software C++ 24.5.1
Welcome to the Autonomy Software repository of the Mars Rover Design Team (MRDT) at Missouri University of Science and Technology (Missouri S&T)! API reference contains the source code and other resources for the development of the autonomy software for our Mars rover. The Autonomy Software project aims to compete in the University Rover Challenge (URC) by demonstrating advanced autonomous capabilities and robust navigation algorithms.
|
This class encapsulates the fundamental principles of Proportional-Integral-Derivative (PID) control with an additional feedforward component. It provides a versatile control mechanism for various systems, enabling precise control of processes by adjusting an output in response to the error between a desired setpoint and a measured process variable. More...
#include <PIDController.h>
Public Member Functions | |
PIDController (const double dKp, const double dKi, const double dKd, const double dKff=0.0) | |
Construct a new PIDController::PIDController object. | |
double | Calculate (const double dActual, const double dSetpoint) |
Calculate the next control output given the current actual and a setpoint. | |
double | Calculate (const double dActual) |
Calculate the next control output given the current actual and using the previously set setpoint. | |
double | Calculate () |
Calculates the control output using the last provided setpoint and actual. | |
void | EnableContinuousInput (const double dMinimumInput, const double dMaximumInput) |
Enables continuous wraparound of PID controller input. Use for setpoints that exists on a circle. For example, if using degrees for setpoint and actual calling this method with 0, 360 will treat 0 and 360 as the same number. This prevents the controller from going the long way around the circle when the setpoint and actual are near the wraparound point. | |
void | DisableContinuousInput () |
Disable continuous input wraparound of the PID controller. | |
void | Reset () |
Resets the controller. This erases the integral term buildup, and removes derivative term on the next iteration. | |
void | SetProportional (const double dKp) |
Configure the proportional gain parameter. This quickly responds to changes in setpoint, and provides most of the initial driving force to make corrections. Some systems can be used with only a P gain, and many can be operated with only PI. For position based controllers, Proportional gain the first parameter to tune, with integral gain second. For rate controlled systems, Proportional is often the second after feedforward. | |
void | SetIntegral (const double dKi) |
Configure the integral gain parameter. This is used for overcoming disturbances, and ensuring that the controller always minimizes error, when the control actual is close to the setpoint. Typically tuned second for "Position" based modes, and third for "Rate" or continuous based modes. | |
void | SetDerivative (const double dKd) |
Configure the derivative gain parameter. This acts as a brake or dampener on the control effort. The more the controller tries to change the value, the more it counteracts the effort. Typically this Parameter is tuned last and only used to reduce overshoot in systems. When using derivative gain, you can usually get a more responsive controller by over-tuning proportional gain so that small oscillations are visible and then bringing derivative gain up until the oscillations disappear. | |
void | SetFeedforward (const double dKff) |
Configure the feedforward gain parameter. This is excellent for velocity, rate, and other continuous control modes where you can expect a rough output value based solely on the setpoint. This should not be used in "position" based control modes. | |
void | SetPID (const double dKp, const double dKi, const double dKd) |
Mutator for PID gains of the controller. | |
void | SetPID (const double dKp, const double dKi, const double dKd, const double dKff) |
Mutator for PID and Feedforward gains of the controller. | |
void | SetSetpoint (const double dSetpoint) |
Mutator for the setpoint for the PID controller. | |
void | SetMaxSetpointDifference (const double dMaxSetpointDifference) |
Mutator for the maximum allowable distance of the setpoint from the actual value. This doesn't limit the setable value of the setpoint. It only limits the value that the controller is given specify the error from the setpoint. | |
void | SetMaxIntegralEffort (const double dMaxIEffort) |
Mutator for the max value of the integral term during PID calculation. This is useful for preventing integral wind-up runaways. | |
void | SetOutputLimits (const double dMinEffort, const double dMaxEffort) |
Mutator for setting the minimum and maximum allowable values of the control output from the controller. | |
void | SetOutputLimits (const double dMaxMin) |
Mutator for setting the minimum and maximum allowable values of the control output from the controller. | |
void | SetOutputRampRate (const double dOutputRampRate) |
Mutator for the maximum rate that the output can change per iteration. | |
void | SetOutputFilter (const double dStrength) |
Set a filter on the output to reduce sharp oscillations. 0.1 is likely a good starting point. | |
void | SetDirection (const bool bReversed=false) |
Set the operating direction of the PID controller. Set true to reverse PID output. | |
double | GetProportional () const |
Accessor for proportional gain of the PID controller. | |
double | GetIntegral () const |
Accessor for integral gain of the PID controller. | |
double | GetDerivative () const |
Accessor for derivative gain of the PID controller. | |
double | GetFeedforward () const |
Accessor for feedforward gain of the PID controller. | |
double | GetSetpoint () const |
Accessor for the current setpoint that the controller is trying to reach. | |
double | GetMaxSetpointDifference () const |
Accessor for the maximum allowable difference the setpoint can be from the actual. Doesn't limit the setpoint, just the max error. 0 = disabled. | |
double | GetMaxIntegralEffort () const |
Accessor for the maximum contribution of the integral term within the controller. 0 = disabled. | |
double | GetOutputRampRate () const |
Accessor the the maximum allowed output ramp rate of the PID controller. | |
double | GetOutputFilter () const |
Accessor for the exponential rolling sum filter strength. Used to reduce sharp output oscillations or jumps. | |
double | GetContinuousInputEnabled () const |
bool | GetReversed () const |
Accessor for if the controller outputs are set to be negated or reversed. | |
Private Member Functions | |
void | CheckGainSigns () |
To operate correctly, all PID parameters require the same sign. | |
This class encapsulates the fundamental principles of Proportional-Integral-Derivative (PID) control with an additional feedforward component. It provides a versatile control mechanism for various systems, enabling precise control of processes by adjusting an output in response to the error between a desired setpoint and a measured process variable.
The key features of this class include:
Additionally, this PID controller offers an optional wraparound feature. When enabled, it can be used for systems with non-linear, circular, or cyclic setpoints, effectively managing control in such scenarios.
This class is a valuable tool for control engineering, robotics, and automation, allowing you to fine-tune the control behavior of various processes and systems.
For specific details on class attributes and methods, please refer to the class documentation.
controllers::PIDController::PIDController | ( | const double | dKp, |
const double | dKi, | ||
const double | dKd, | ||
const double | dKff = 0.0 |
||
) |
Construct a new PIDController::PIDController object.
dKp | - The proportional gain (Kp) component adjusts the control output in proportion to the current error. |
dKi | - The integral gain (Ki) component accumulates past errors to eliminate steady-state error. |
dKd | - The derivative gain (Kd) component anticipates future error by considering the rate of change of the error. |
dKff | - The feedforward gain (Kff) allows for predictive control, improving response time and minimizing overshoot. |
double controllers::PIDController::Calculate | ( | const double | dActual, |
const double | dSetpoint | ||
) |
Calculate the next control output given the current actual and a setpoint.
dActual | - The current actual position of the system. |
dSetpoint | - The desired setpoint of the controller. |
double controllers::PIDController::Calculate | ( | const double | dActual | ) |
Calculate the next control output given the current actual and using the previously set setpoint.
dActual | - The current actual position of the system. |
double controllers::PIDController::Calculate | ( | ) |
Calculates the control output using the last provided setpoint and actual.
void controllers::PIDController::EnableContinuousInput | ( | const double | dMinimumInput, |
const double | dMaximumInput | ||
) |
Enables continuous wraparound of PID controller input. Use for setpoints that exists on a circle. For example, if using degrees for setpoint and actual calling this method with 0, 360 will treat 0 and 360 as the same number. This prevents the controller from going the long way around the circle when the setpoint and actual are near the wraparound point.
dMinimumInput | - Minimum input before wraparound. |
dMaximumInput | - Maximum input before wraparound. |
void controllers::PIDController::DisableContinuousInput | ( | ) |
Disable continuous input wraparound of the PID controller.
void controllers::PIDController::Reset | ( | ) |
Resets the controller. This erases the integral term buildup, and removes derivative term on the next iteration.
void controllers::PIDController::SetProportional | ( | const double | dKp | ) |
Configure the proportional gain parameter. This quickly responds to changes in setpoint, and provides most of the initial driving force to make corrections. Some systems can be used with only a P gain, and many can be operated with only PI. For position based controllers, Proportional gain the first parameter to tune, with integral gain second. For rate controlled systems, Proportional is often the second after feedforward.
dKp | - The proportional gain for the controller to use for calculation. |
void controllers::PIDController::SetIntegral | ( | const double | dKi | ) |
Configure the integral gain parameter. This is used for overcoming disturbances, and ensuring that the controller always minimizes error, when the control actual is close to the setpoint. Typically tuned second for "Position" based modes, and third for "Rate" or continuous based modes.
dKi | - The integral gain for the controller to use for calculation. |
void controllers::PIDController::SetDerivative | ( | const double | dKd | ) |
Configure the derivative gain parameter. This acts as a brake or dampener on the control effort. The more the controller tries to change the value, the more it counteracts the effort. Typically this Parameter is tuned last and only used to reduce overshoot in systems. When using derivative gain, you can usually get a more responsive controller by over-tuning proportional gain so that small oscillations are visible and then bringing derivative gain up until the oscillations disappear.
dKd | - The derivative gain for the controller to use for calculation. |
void controllers::PIDController::SetFeedforward | ( | const double | dKff | ) |
Configure the feedforward gain parameter. This is excellent for velocity, rate, and other continuous control modes where you can expect a rough output value based solely on the setpoint. This should not be used in "position" based control modes.
dKff | - The feedforward gain for the controller to use for calculation. |
void controllers::PIDController::SetPID | ( | const double | dKp, |
const double | dKi, | ||
const double | dKd | ||
) |
Mutator for PID gains of the controller.
dKp | - The proportional gain for the controller to use for calculation. |
dKi | - The integral gain for the controller to use for calculation. |
dKd | - The derivative gain for the controller to use for calculation. |
void controllers::PIDController::SetPID | ( | const double | dKp, |
const double | dKi, | ||
const double | dKd, | ||
const double | dKff | ||
) |
Mutator for PID and Feedforward gains of the controller.
dKp | - The proportional gain for the controller to use for calculation. |
dKi | - The integral gain for the controller to use for calculation. |
dKd | - The derivative gain for the controller to use for calculation. |
dKff | - The feedforward gain for the controller to use for calculation. |
void controllers::PIDController::SetSetpoint | ( | const double | dSetpoint | ) |
Mutator for the setpoint for the PID controller.
dSetpoint | - The setpoint that the controller should aim to get the actual to. |
void controllers::PIDController::SetMaxSetpointDifference | ( | const double | dMaxSetpointDifference | ) |
Mutator for the maximum allowable distance of the setpoint from the actual value. This doesn't limit the setable value of the setpoint. It only limits the value that the controller is given specify the error from the setpoint.
dMaxSetpointDifference | - The allowable distance of the setpoint from the actual. |
void controllers::PIDController::SetMaxIntegralEffort | ( | const double | dMaxIEffort | ) |
Mutator for the max value of the integral term during PID calculation. This is useful for preventing integral wind-up runaways.
dMaxIEffort | - The max allowable value of the integral term. |
void controllers::PIDController::SetOutputLimits | ( | const double | dMinEffort, |
const double | dMaxEffort | ||
) |
Mutator for setting the minimum and maximum allowable values of the control output from the controller.
dMinEffort | - The minimum allowable output from the PID controller. |
dMaxEffort | - The maximum allowable output from the PID controller. |
void controllers::PIDController::SetOutputLimits | ( | const double | dMinMax | ) |
Mutator for setting the minimum and maximum allowable values of the control output from the controller.
dMinMax | - The overall output range of the controller. Must be positive. |
void controllers::PIDController::SetOutputRampRate | ( | const double | dOutputRampRate | ) |
Mutator for the maximum rate that the output can change per iteration.
dOutputRampRate | - The maximum ramp rate of the output for the controller. |
void controllers::PIDController::SetOutputFilter | ( | const double | dStrength | ) |
Set a filter on the output to reduce sharp oscillations. 0.1 is likely a good starting point.
dStrength | - The output filtering strength. |
void controllers::PIDController::SetDirection | ( | const bool | bReversed = false | ) |
Set the operating direction of the PID controller. Set true to reverse PID output.
bReversed | - Whether or not eh PID output should be negated. |
double controllers::PIDController::GetProportional | ( | ) | const |
Accessor for proportional gain of the PID controller.
double controllers::PIDController::GetIntegral | ( | ) | const |
Accessor for integral gain of the PID controller.
double controllers::PIDController::GetDerivative | ( | ) | const |
Accessor for derivative gain of the PID controller.
double controllers::PIDController::GetFeedforward | ( | ) | const |
Accessor for feedforward gain of the PID controller.
double controllers::PIDController::GetSetpoint | ( | ) | const |
Accessor for the current setpoint that the controller is trying to reach.
double controllers::PIDController::GetMaxSetpointDifference | ( | ) | const |
Accessor for the maximum allowable difference the setpoint can be from the actual. Doesn't limit the setpoint, just the max error. 0 = disabled.
double controllers::PIDController::GetMaxIntegralEffort | ( | ) | const |
Accessor for the maximum contribution of the integral term within the controller. 0 = disabled.
double controllers::PIDController::GetOutputRampRate | ( | ) | const |
Accessor the the maximum allowed output ramp rate of the PID controller.
double controllers::PIDController::GetOutputFilter | ( | ) | const |
Accessor for the exponential rolling sum filter strength. Used to reduce sharp output oscillations or jumps.
bool controllers::PIDController::GetReversed | ( | ) | const |
Accessor for if the controller outputs are set to be negated or reversed.
|
private |
To operate correctly, all PID parameters require the same sign.