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.
Loading...
Searching...
No Matches
controllers::PIDController Class Reference

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.
 

Private Attributes

double m_dKp
 
double m_dKi
 
double m_dKd
 
double m_dKff
 
double m_dSetpoint
 
double m_dErrorSum
 
double m_dMaxError
 
double m_dMaxIEffort
 
double m_dMinEffort
 
double m_dMaxEffort
 
double m_dLastActual
 
double m_dOutputRampRate
 
double m_dLastControlOutput
 
double m_dOutputFilter
 
double m_dMaxSetpointDifference
 
double m_dMinimumContinuousInput
 
double m_dMaximumContinuousInput
 
bool m_bControllerIsContinuous
 
bool m_bFirstCalculation
 
bool m_bReversed
 

Detailed Description

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:

  • Proportional Control: The proportional gain (Kp) component adjusts the control output in proportion to the current error.
  • Integral Control: The integral gain (Ki) component accumulates past errors to eliminate steady-state error.
  • Derivative Control: The derivative gain (Kd) component anticipates future error by considering the rate of change of the error.
  • Feedforward Control: The feedforward gain (Kff) allows for predictive control, improving response time and minimizing overshoot. See https://blog.opticontrols.com/archives/297 for a better explanation on feedforward controller.

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.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-16

Constructor & Destructor Documentation

◆ PIDController()

controllers::PIDController::PIDController ( const double  dKp,
const double  dKi,
const double  dKd,
const double  dKff = 0.0 
)

Construct a new PIDController::PIDController object.

Parameters
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.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
40 {
41 // Initialize member variable.
42 m_dKp = dKp;
43 m_dKi = dKi;
44 m_dKd = dKd;
45 m_dKff = dKff;
46 m_dSetpoint = 0.0;
47 m_dErrorSum = 0.0;
48 m_dMaxError = 0.0;
49 m_dMaxIEffort = 0.0;
50 m_dMinEffort = 0.0;
51 m_dMaxEffort = 0.0;
52 m_dLastActual = 0.0;
53 m_dOutputRampRate = 0.0;
54 m_dLastControlOutput = 0.0;
55 m_dOutputFilter = 0.0;
56 m_dMaxSetpointDifference = 0.0;
57 m_dMinimumContinuousInput = 0.0;
58 m_dMaximumContinuousInput = 360.0;
59 m_bControllerIsContinuous = false;
60 m_bFirstCalculation = true;
61 m_bReversed = false;
62 }

Member Function Documentation

◆ Calculate() [1/3]

double controllers::PIDController::Calculate ( const double  dActual,
const double  dSetpoint 
)

Calculate the next control output given the current actual and a setpoint.

Parameters
dActual- The current actual position of the system.
dSetpoint- The desired setpoint of the controller.
Returns
double - The resultant PID controller output.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
75 {
76 // Create instance variables.
77 double dPTermOutput;
78 double dITermOutput;
79 double dDTermOutput;
80 double dFFTermOutput;
81 double dOutput;
82
83 // Update setpoint member variable.
84 m_dSetpoint = dSetpoint;
85
86 // Apply the sliding setpoint range adjust if necessary.
87 if (m_dMaxSetpointDifference != 0)
88 {
89 // Clamp current setpoint value within a certain range of the current actual.
90 m_dSetpoint = numops::Clamp(m_dSetpoint, dActual - m_dMaxSetpointDifference, dActual + m_dMaxSetpointDifference);
91 }
92
93 // Determine error from setpoint.
94 double dError = dSetpoint - dActual;
95
96 // Check if the input, and therefor controller is continuous.
97 if (m_bControllerIsContinuous)
98 {
99 // Calculate error bounds.
100 double dErrorBound = (m_dMaximumContinuousInput - m_dMinimumContinuousInput) / 2.0;
101 // Wrap heading.
102 dError = numops::InputAngleModulus(dError, -dErrorBound, dErrorBound);
103 }
104
105 // Calculate feedforward term.
106 dFFTermOutput = m_dKff * dSetpoint;
107 // Calculate proportional term.
108 dPTermOutput = m_dKp * dError;
109
110 // Check if this is the first time doing a calculation.
111 if (m_bFirstCalculation)
112 {
113 // Assume the process variable hold same as previous.
114 m_dLastActual = dActual;
115 // Assume the last output is the current time-independent output.
116 m_dLastControlOutput = dPTermOutput + dFFTermOutput;
117
118 // Set first calculation toggle to false.
119 m_bFirstCalculation = false;
120 }
121
122 // Calculate derivative term.
123 // Note, derivative is actually negative and "slows" the system if it's doing
124 // the correct thing. Small gain values help prevent output spikes and overshoot.
125 dDTermOutput = -m_dKd * (dActual - m_dLastActual);
126 m_dLastActual = dActual;
127
128 // Calculate integral term.
129 // The integral term is more complex. There's several things to factor in to make it easier to deal with.
130 // 1. m_dMaxIEffort restricts the amount of output contributed by the integral term.
131 // 2. prevent windup by not increasing errorSum if we're already running against our max Ioutput
132 // 3. prevent windup by not increasing errorSum if output is output=maxOutput
133 dITermOutput = m_dKi * m_dErrorSum;
134 // Apply integral term limits.
135 if (m_dMaxIEffort != 0)
136 {
137 // Clamp current integral term output.
138 dITermOutput = numops::Clamp(dITermOutput, -m_dMaxIEffort, m_dMaxIEffort);
139 }
140
141 // Here's PID!
142 dOutput = dFFTermOutput + dPTermOutput + dITermOutput + dDTermOutput;
143 // Check if error is at not at limits.
144 if (m_dMinEffort != m_dMaxEffort && !numops::Bounded(dOutput, m_dMinEffort, m_dMaxEffort))
145 {
146 // Reset the error to a sane level. Settings to the current error ensures a smooth transition when the P term
147 // decreases enough for the I term to start acting upon the controller properly.
148 m_dErrorSum = dError;
149 }
150 // Check if the error is within the allowed ramp rate compared to the last output.
151 else if (m_dOutputRampRate != 0 && !numops::Bounded(dOutput, m_dLastControlOutput - m_dOutputRampRate, m_dLastControlOutput + m_dOutputRampRate))
152 {
153 // Reset the error to a sane level. Settings to the current error ensures a smooth transition when the P term
154 // decreases enough for the I term to start acting upon the controller properly.
155 m_dErrorSum = dError;
156 }
157 // Check if integral term output should be limited.
158 else if (m_dMaxIEffort != 0)
159 {
160 // In addition to output limiting directly, we also want to prevent integral term wind-up. Restrict directly.
161 m_dErrorSum = numops::Clamp(m_dErrorSum + dError, -m_dMaxError, m_dMaxError);
162 }
163 else
164 {
165 // Accumulate error.
166 m_dErrorSum += dError;
167 }
168
169 // Restrict output to our specified ramp limits.
170 if (m_dOutputRampRate != 0)
171 {
172 // Clamp output to ramp rate.
173 dOutput = numops::Clamp(dOutput, m_dLastControlOutput - m_dOutputRampRate, m_dLastControlOutput + m_dOutputRampRate);
174 }
175 // Restrict output to our specified effort limits.
176 if (m_dMinEffort != m_dMaxEffort)
177 {
178 // Clamp output to effort limits.
179 dOutput = numops::Clamp(dOutput, m_dMinEffort, m_dMaxEffort);
180 }
181 // Reduce jitters and output spikes with an exponential rolling sum filter.
182 if (m_dOutputFilter != 0)
183 {
184 // Filter output effort.
185 dOutput = (m_dLastControlOutput * m_dOutputFilter) + (dOutput * (1 - m_dOutputFilter));
186 }
187
188 // Update last output member variable.
189 m_dLastControlOutput = dOutput;
190
191 // Return the PID controller calculated output effort.
192 return dOutput;
193 }
constexpr T Clamp(T tValue, T tMin, T tMax)
Clamps a given value from going above or below a given threshold.
Definition NumberOperations.hpp:81
constexpr T InputAngleModulus(T tValue, T tMinValue, T tMaxValue)
Calculates the modulus of an input angle.
Definition NumberOperations.hpp:165
bool Bounded(T tValue, T tMin, T tMax, const bool bInclusive=true)
Checks if a given value is between the given maximum and minimum ranges.
Definition NumberOperations.hpp:101
Here is the call graph for this function:
Here is the caller graph for this function:

◆ Calculate() [2/3]

double controllers::PIDController::Calculate ( const double  dActual)

Calculate the next control output given the current actual and using the previously set setpoint.

Parameters
dActual- The current actual position of the system.
Returns
double - The resultant PID controller output.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
206 {
207 // Calculate and return the output from the PIDController using the same setpoint.
208 return this->Calculate(dActual, m_dSetpoint);
209 }
double Calculate()
Calculates the control output using the last provided setpoint and actual.
Definition PIDController.cpp:219
Here is the call graph for this function:

◆ Calculate() [3/3]

double controllers::PIDController::Calculate ( )

Calculates the control output using the last provided setpoint and actual.

Returns
double - The resultant PID controller output.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
220 {
221 // Calculate and return the output from the PIDController using the previous actual and setpoint.
222 return this->Calculate(m_dLastActual, m_dSetpoint);
223 }
Here is the call graph for this function:
Here is the caller graph for this function:

◆ EnableContinuousInput()

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.

Parameters
dMinimumInput- Minimum input before wraparound.
dMaximumInput- Maximum input before wraparound.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
239 {
240 // Assign member variables.
241 m_dMinimumContinuousInput = dMinimumInput;
242 m_dMaximumContinuousInput = dMaximumInput;
243
244 // Enable continuous input.
245 m_bControllerIsContinuous = true;
246 }
Here is the caller graph for this function:

◆ DisableContinuousInput()

void controllers::PIDController::DisableContinuousInput ( )

Disable continuous input wraparound of the PID controller.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
256 {
257 // Disable continuous input.
258 m_bControllerIsContinuous = false;
259 }
Here is the caller graph for this function:

◆ Reset()

void controllers::PIDController::Reset ( )

Resets the controller. This erases the integral term buildup, and removes derivative term on the next iteration.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
270 {
271 // Reset necessary values to reset the controller.
272 m_bFirstCalculation = true;
273 m_dErrorSum = 0.0;
274 }
Here is the caller graph for this function:

◆ SetProportional()

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.

Parameters
dKp- The proportional gain for the controller to use for calculation.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
289 {
290 // Assign member variables.
291 m_dKp = dKp;
292
293 // Check signs of gains.
294 this->CheckGainSigns();
295 }
void CheckGainSigns()
To operate correctly, all PID parameters require the same sign.
Definition PIDController.cpp:699
Here is the call graph for this function:
Here is the caller graph for this function:

◆ SetIntegral()

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.

Parameters
dKi- The integral gain for the controller to use for calculation.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
308 {
309 // Check if the current I gain is not zero and we need to scale our current error.
310 if (m_dKi != 0)
311 {
312 // Scale the current error sum, to match the new integral gain.
313 m_dErrorSum = m_dErrorSum * (m_dKi / dKi);
314 }
315 // Check if max integral term effort is enabled.
316 if (m_dMaxIEffort != 0)
317 {
318 // Update max error from new integral and max effort.
319 m_dMaxError = m_dMaxIEffort / dKi;
320 }
321
322 // Assign integral gain member variable.
323 m_dKi = dKi;
324
325 // Check the signs of the PID gains.
326 this->CheckGainSigns();
327 }
Here is the call graph for this function:
Here is the caller graph for this function:

◆ SetDerivative()

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.

Parameters
dKd- The derivative gain for the controller to use for calculation.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
342 {
343 // Assign member variables.
344 m_dKd = dKd;
345
346 // Check signs of gains.
347 this->CheckGainSigns();
348 }
Here is the call graph for this function:
Here is the caller graph for this function:

◆ SetFeedforward()

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.

Parameters
dKff- The feedforward gain for the controller to use for calculation.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
361 {
362 // Assign member variables.
363 m_dKff = dKff;
364
365 // Check signs of gains.
366 this->CheckGainSigns();
367 }
Here is the call graph for this function:
Here is the caller graph for this function:

◆ SetPID() [1/2]

void controllers::PIDController::SetPID ( const double  dKp,
const double  dKi,
const double  dKd 
)

Mutator for PID gains of the controller.

Parameters
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.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
380 {
381 // Update member variables.
382 m_dKp = dKp;
383 m_dKd = dKd;
384
385 // Call SetIntegral since is scales the accumulated error and checks signs.
386 this->SetIntegral(dKi);
387 }
void SetIntegral(const double dKi)
Configure the integral gain parameter. This is used for overcoming disturbances, and ensuring that th...
Definition PIDController.cpp:307
Here is the call graph for this function:
Here is the caller graph for this function:

◆ SetPID() [2/2]

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.

Parameters
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.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
401 {
402 // Update member variables.
403 m_dKp = dKp;
404 m_dKd = dKd;
405 m_dKff = dKff;
406
407 // Call SetIntegral since is scales the accumulated error and checks signs.
408 this->SetIntegral(dKi);
409 }
Here is the call graph for this function:

◆ SetSetpoint()

void controllers::PIDController::SetSetpoint ( const double  dSetpoint)

Mutator for the setpoint for the PID controller.

Parameters
dSetpoint- The setpoint that the controller should aim to get the actual to.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
420 {
421 // Assign member variable.
422 m_dSetpoint = dSetpoint;
423 }
Here is the caller graph for this function:

◆ SetMaxSetpointDifference()

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.

Parameters
dMaxSetpointDifference- The allowable distance of the setpoint from the actual.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
436 {
437 // Assign member variables.
438 m_dMaxSetpointDifference = dMaxSetpointDifference;
439 }
Here is the caller graph for this function:

◆ SetMaxIntegralEffort()

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.

Parameters
dMaxIEffort- The max allowable value of the integral term.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
451 {
452 // Assign member variable.
453 m_dMaxIEffort = dMaxIEffort;
454 }
Here is the caller graph for this function:

◆ SetOutputLimits() [1/2]

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.

Parameters
dMinEffort- The minimum allowable output from the PID controller.
dMaxEffort- The maximum allowable output from the PID controller.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
467 {
468 // Check if the maximum is greater than the minimum.
469 if (dMaxEffort > dMinEffort)
470 {
471 // Assign member variables.
472 m_dMinEffort = dMinEffort;
473 m_dMaxEffort = dMaxEffort;
474
475 // Ensure the bounds of the integral term are within the bounds of the allowable output range.
476 if (m_dMaxIEffort == 0 || m_dMaxIEffort > (dMaxEffort - dMinEffort))
477 {
478 // Set new integral max output.
479 this->SetMaxIntegralEffort(dMaxEffort - dMinEffort);
480 }
481 }
482 }
void SetMaxIntegralEffort(const double dMaxIEffort)
Mutator for the max value of the integral term during PID calculation. This is useful for preventing ...
Definition PIDController.cpp:450
Here is the call graph for this function:
Here is the caller graph for this function:

◆ SetOutputLimits() [2/2]

void controllers::PIDController::SetOutputLimits ( const double  dMinMax)

Mutator for setting the minimum and maximum allowable values of the control output from the controller.

Parameters
dMinMax- The overall output range of the controller. Must be positive.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
494 {
495 // Set output limits with the same max and min.
496 this->SetOutputLimits(-dMinMax, dMinMax);
497 }
void SetOutputLimits(const double dMinEffort, const double dMaxEffort)
Mutator for setting the minimum and maximum allowable values of the control output from the controlle...
Definition PIDController.cpp:466
Here is the call graph for this function:

◆ SetOutputRampRate()

void controllers::PIDController::SetOutputRampRate ( const double  dOutputRampRate)

Mutator for the maximum rate that the output can change per iteration.

Parameters
dOutputRampRate- The maximum ramp rate of the output for the controller.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
508 {
509 // Assign member variable.
510 m_dOutputRampRate = dOutputRampRate;
511 }
Here is the caller graph for this function:

◆ SetOutputFilter()

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.

Parameters
dStrength- The output filtering strength.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
523 {
524 // Check if the strength is valid.
525 if (dStrength == 0 || numops::Bounded(dStrength, 0.0, 1.0))
526 {
527 // Assign member variable.
528 m_dOutputFilter = dStrength;
529 }
530 }
Here is the call graph for this function:
Here is the caller graph for this function:

◆ SetDirection()

void controllers::PIDController::SetDirection ( const bool  bReversed = false)

Set the operating direction of the PID controller. Set true to reverse PID output.

Parameters
bReversed- Whether or not eh PID output should be negated.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
542 {
543 // Assign member variable.
544 m_bReversed = bReversed;
545 }
Here is the caller graph for this function:

◆ GetProportional()

double controllers::PIDController::GetProportional ( ) const

Accessor for proportional gain of the PID controller.

Returns
double - dKp proportional gain of the controller.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
556 {
557 // Return the member variable.
558 return m_dKp;
559 }
Here is the caller graph for this function:

◆ GetIntegral()

double controllers::PIDController::GetIntegral ( ) const

Accessor for integral gain of the PID controller.

Returns
double - dKi integral gain of the controller.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
570 {
571 // Return the member variable.
572 return m_dKi;
573 }
Here is the caller graph for this function:

◆ GetDerivative()

double controllers::PIDController::GetDerivative ( ) const

Accessor for derivative gain of the PID controller.

Returns
double - dKd derivative gain of the controller.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
584 {
585 // Return the member variable.
586 return m_dKd;
587 }
Here is the caller graph for this function:

◆ GetFeedforward()

double controllers::PIDController::GetFeedforward ( ) const

Accessor for feedforward gain of the PID controller.

Returns
double - dKff feedforward gain of the controller.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
598 {
599 // Return the member variable.
600 return m_dKff;
601 }
Here is the caller graph for this function:

◆ GetSetpoint()

double controllers::PIDController::GetSetpoint ( ) const

Accessor for the current setpoint that the controller is trying to reach.

Returns
double - The current setpoint.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
612 {
613 // Return the member variable.
614 return m_dSetpoint;
615 }
Here is the caller graph for this function:

◆ GetMaxSetpointDifference()

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.

Returns
double - The maximum setpoint difference from the actual.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
628 {
629 // Return the member variable.
630 return m_dMaxSetpointDifference;
631 }
Here is the caller graph for this function:

◆ GetMaxIntegralEffort()

double controllers::PIDController::GetMaxIntegralEffort ( ) const

Accessor for the maximum contribution of the integral term within the controller. 0 = disabled.

Returns
double - The maximum allowed integral value.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
643 {
644 // Return the member variable.
645 return m_dMaxIEffort;
646 }
Here is the caller graph for this function:

◆ GetOutputRampRate()

double controllers::PIDController::GetOutputRampRate ( ) const

Accessor the the maximum allowed output ramp rate of the PID controller.

Returns
double - The max ramp rate of the controller output.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
657 {
658 // Return the member variable.
659 return m_dOutputRampRate;
660 }
Here is the caller graph for this function:

◆ GetOutputFilter()

double controllers::PIDController::GetOutputFilter ( ) const

Accessor for the exponential rolling sum filter strength. Used to reduce sharp output oscillations or jumps.

Returns
double - Strength of the output filtering.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
672 {
673 // Return the member variable.
674 return m_dOutputFilter;
675 }
Here is the caller graph for this function:

◆ GetReversed()

bool controllers::PIDController::GetReversed ( ) const

Accessor for if the controller outputs are set to be negated or reversed.

Returns
true - The output is negated.
false - The output is not negated.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-19
687 {
688 // Return the member variable.
689 return m_bReversed;
690 }
Here is the caller graph for this function:

◆ CheckGainSigns()

void controllers::PIDController::CheckGainSigns ( )
private

To operate correctly, all PID parameters require the same sign.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-17
700 {
701 // Check if the gains are supposed to be reversed.
702 if (m_bReversed)
703 {
704 // All values should be below zero.
705 if (m_dKp > 0)
706 {
707 // Flip sign sign for proportional gain.
708 m_dKi *= -1;
709 }
710 if (m_dKi > 0)
711 {
712 // Flip sign for integral gain.
713 m_dKi *= -1;
714 }
715 if (m_dKd > 0)
716 {
717 // Flip sign for derivative gain.
718 m_dKd *= -1;
719 }
720 if (m_dKff > 0)
721 {
722 // Flip sign for feedforward gain.
723 m_dKff *= -1;
724 }
725 }
726 else
727 {
728 // All values should be above zero.
729 if (m_dKp < 0)
730 {
731 // Flip sign sign for proportional gain.
732 m_dKi *= -1;
733 }
734 if (m_dKi < 0)
735 {
736 // Flip sign for integral gain.
737 m_dKi *= -1;
738 }
739 if (m_dKd < 0)
740 {
741 // Flip sign for derivative gain.
742 m_dKd *= -1;
743 }
744 if (m_dKff < 0)
745 {
746 // Flip sign for feedforward gain.
747 m_dKff *= -1;
748 }
749 }
750 }
Here is the caller graph for this function:

The documentation for this class was generated from the following files: