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
PIDController.h
Go to the documentation of this file.
1
11#ifndef PID_CONTROLLER_H
12#define PID_CONTROLLER_H
13
14
23namespace controllers
24{
25
26
50 {
51 public:
53 // Declare public enums that are specific to and used withing this class.
55
57 // Declare public methods and member variables.
59
60 PIDController(const double dKp, const double dKi, const double dKd, const double dKff = 0.0);
61 double Calculate(const double dActual, const double dSetpoint);
62 double Calculate(const double dActual);
63 double Calculate();
64 void EnableContinuousInput(const double dMinimumInput, const double dMaximumInput);
66 void Reset();
67
69 // Setters
71
72 void SetProportional(const double dKp);
73 void SetIntegral(const double dKi);
74 void SetDerivative(const double dKd);
75 void SetFeedforward(const double dKff);
76 void SetPID(const double dKp, const double dKi, const double dKd);
77 void SetPID(const double dKp, const double dKi, const double dKd, const double dKff);
78 void SetSetpoint(const double dSetpoint);
79 void SetMaxSetpointDifference(const double dMaxSetpointDifference);
80 void SetMaxIntegralEffort(const double dMaxIEffort);
81 void SetOutputLimits(const double dMinEffort, const double dMaxEffort);
82 void SetOutputLimits(const double dMaxMin);
83 void SetOutputRampRate(const double dOutputRampRate);
84 void SetOutputFilter(const double dStrength);
85 void SetDirection(const bool bReversed = false);
86
88 // Getters
90
91 double GetProportional() const;
92 double GetIntegral() const;
93 double GetDerivative() const;
94 double GetFeedforward() const;
95 double GetSetpoint() const;
96 double GetMaxSetpointDifference() const;
97 double GetMaxIntegralEffort() const;
98 double GetOutputRampRate() const;
99 double GetOutputFilter() const;
100 double GetContinuousInputEnabled() const;
101 bool GetReversed() const;
102
103 private:
105 // Declare public methods.
107
108 void CheckGainSigns();
109
111 // Declare private member variables.
113
114 double m_dKp; // Proportional gain.
115 double m_dKi; // Integral gain.
116 double m_dKd; // Derivative gain.
117 double m_dKff; // Feedforward gain.
118 double m_dSetpoint; // Current control setpoint.
119 double m_dErrorSum; // Error accumulation.
120 double m_dMaxError; // Max allowed error.
121 double m_dMaxIEffort; // Max integral calculated term effort.
122 double m_dMinEffort; // Min output of the PID controller.
123 double m_dMaxEffort; // Max output of the PID controller.
124 double m_dLastActual; // The previous process variable input.
125 double m_dOutputRampRate; // The max rate of change of the controller output.
126 double m_dLastControlOutput; // The previous control output of the controller.
127 double m_dOutputFilter; // Strength of an exponential rolling sum filter. Used to reduce sharp oscillations.
128 double m_dMaxSetpointDifference; // Limit on how far the setpoint can be from the current position.
129 double m_dMinimumContinuousInput; // The minimum wraparound value of the input for the controller.
130 double m_dMaximumContinuousInput; // The maximum wraparound value of the input for the controller.
131 bool m_bControllerIsContinuous; // Whether of not the controller is working with a circular position range. Good for setpoints that use degrees.
132 bool m_bFirstCalculation; // Whether or not this is the first iteration of the control loop.
133 bool m_bReversed; // Operating direction of the controller.
134 };
135} // namespace controllers
136#endif
This class encapsulates the fundamental principles of Proportional-Integral-Derivative (PID) control ...
Definition PIDController.h:50
void SetDerivative(const double dKd)
Configure the derivative gain parameter. This acts as a brake or dampener on the control effort....
Definition PIDController.cpp:341
bool GetReversed() const
Accessor for if the controller outputs are set to be negated or reversed.
Definition PIDController.cpp:686
void CheckGainSigns()
To operate correctly, all PID parameters require the same sign.
Definition PIDController.cpp:699
double GetOutputFilter() const
Accessor for the exponential rolling sum filter strength. Used to reduce sharp output oscillations or...
Definition PIDController.cpp:671
double GetSetpoint() const
Accessor for the current setpoint that the controller is trying to reach.
Definition PIDController.cpp:611
void SetMaxSetpointDifference(const double dMaxSetpointDifference)
Mutator for the maximum allowable distance of the setpoint from the actual value. This doesn't limit ...
Definition PIDController.cpp:435
void SetPID(const double dKp, const double dKi, const double dKd)
Mutator for PID gains of the controller.
Definition PIDController.cpp:379
double GetIntegral() const
Accessor for integral gain of the PID controller.
Definition PIDController.cpp:569
void SetIntegral(const double dKi)
Configure the integral gain parameter. This is used for overcoming disturbances, and ensuring that th...
Definition PIDController.cpp:307
double GetFeedforward() const
Accessor for feedforward gain of the PID controller.
Definition PIDController.cpp:597
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
double GetProportional() const
Accessor for proportional gain of the PID controller.
Definition PIDController.cpp:555
void SetOutputRampRate(const double dOutputRampRate)
Mutator for the maximum rate that the output can change per iteration.
Definition PIDController.cpp:507
void SetOutputFilter(const double dStrength)
Set a filter on the output to reduce sharp oscillations. 0.1 is likely a good starting point.
Definition PIDController.cpp:522
double GetDerivative() const
Accessor for derivative gain of the PID controller.
Definition PIDController.cpp:583
double GetOutputRampRate() const
Accessor the the maximum allowed output ramp rate of the PID controller.
Definition PIDController.cpp:656
void SetFeedforward(const double dKff)
Configure the feedforward gain parameter. This is excellent for velocity, rate, and other continuous ...
Definition PIDController.cpp:360
void EnableContinuousInput(const double dMinimumInput, const double dMaximumInput)
Enables continuous wraparound of PID controller input. Use for setpoints that exists on a circle....
Definition PIDController.cpp:238
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
double GetMaxIntegralEffort() const
Accessor for the maximum contribution of the integral term within the controller. 0 = disabled.
Definition PIDController.cpp:642
void SetProportional(const double dKp)
Configure the proportional gain parameter. This quickly responds to changes in setpoint,...
Definition PIDController.cpp:288
void SetSetpoint(const double dSetpoint)
Mutator for the setpoint for the PID controller.
Definition PIDController.cpp:419
void DisableContinuousInput()
Disable continuous input wraparound of the PID controller.
Definition PIDController.cpp:255
void Reset()
Resets the controller. This erases the integral term buildup, and removes derivative term on the next...
Definition PIDController.cpp:269
double Calculate()
Calculates the control output using the last provided setpoint and actual.
Definition PIDController.cpp:219
double GetMaxSetpointDifference() const
Accessor for the maximum allowable difference the setpoint can be from the actual....
Definition PIDController.cpp:627
void SetDirection(const bool bReversed=false)
Set the operating direction of the PID controller. Set true to reverse PID output.
Definition PIDController.cpp:541
This namespace stores classes, functions, and structs that are used to implement different controller...
Definition PIDController.cpp:26