WPILibC++ 2024.3.2
PIDController.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <functional>
8#include <limits>
9
10#include <wpi/SymbolExports.h>
13
14#include "units/time.h"
15
16namespace frc {
17
18/**
19 * Implements a PID control loop.
20 */
22 : public wpi::Sendable,
23 public wpi::SendableHelper<PIDController> {
24 public:
25 /**
26 * Allocates a PIDController with the given constants for Kp, Ki, and Kd.
27 *
28 * @param Kp The proportional coefficient. Must be >= 0.
29 * @param Ki The integral coefficient. Must be >= 0.
30 * @param Kd The derivative coefficient. Must be >= 0.
31 * @param period The period between controller updates in seconds. The
32 * default is 20 milliseconds. Must be positive.
33 */
34 PIDController(double Kp, double Ki, double Kd,
35 units::second_t period = 20_ms);
36
37 ~PIDController() override = default;
38
39 PIDController(const PIDController&) = default;
43
44 /**
45 * Sets the PID Controller gain parameters.
46 *
47 * Sets the proportional, integral, and differential coefficients.
48 *
49 * @param Kp The proportional coefficient. Must be >= 0.
50 * @param Ki The integral coefficient. Must be >= 0.
51 * @param Kd The differential coefficient. Must be >= 0.
52 */
53 void SetPID(double Kp, double Ki, double Kd);
54
55 /**
56 * Sets the proportional coefficient of the PID controller gain.
57 *
58 * @param Kp The proportional coefficient. Must be >= 0.
59 */
60 void SetP(double Kp);
61
62 /**
63 * Sets the integral coefficient of the PID controller gain.
64 *
65 * @param Ki The integral coefficient. Must be >= 0.
66 */
67 void SetI(double Ki);
68
69 /**
70 * Sets the differential coefficient of the PID controller gain.
71 *
72 * @param Kd The differential coefficient. Must be >= 0.
73 */
74 void SetD(double Kd);
75
76 /**
77 * Sets the IZone range. When the absolute value of the position error is
78 * greater than IZone, the total accumulated error will reset to zero,
79 * disabling integral gain until the absolute value of the position error is
80 * less than IZone. This is used to prevent integral windup. Must be
81 * non-negative. Passing a value of zero will effectively disable integral
82 * gain. Passing a value of infinity disables IZone functionality.
83 *
84 * @param iZone Maximum magnitude of error to allow integral control. Must be
85 * >= 0.
86 */
87 void SetIZone(double iZone);
88
89 /**
90 * Gets the proportional coefficient.
91 *
92 * @return proportional coefficient
93 */
94 double GetP() const;
95
96 /**
97 * Gets the integral coefficient.
98 *
99 * @return integral coefficient
100 */
101 double GetI() const;
102
103 /**
104 * Gets the differential coefficient.
105 *
106 * @return differential coefficient
107 */
108 double GetD() const;
109
110 /**
111 * Get the IZone range.
112 *
113 * @return Maximum magnitude of error to allow integral control.
114 */
115 double GetIZone() const;
116
117 /**
118 * Gets the period of this controller.
119 *
120 * @return The period of the controller.
121 */
122 units::second_t GetPeriod() const;
123
124 /**
125 * Gets the position tolerance of this controller.
126 *
127 * @return The position tolerance of the controller.
128 */
129 double GetPositionTolerance() const;
130
131 /**
132 * Gets the velocity tolerance of this controller.
133 *
134 * @return The velocity tolerance of the controller.
135 */
136 double GetVelocityTolerance() const;
137
138 /**
139 * Sets the setpoint for the PIDController.
140 *
141 * @param setpoint The desired setpoint.
142 */
143 void SetSetpoint(double setpoint);
144
145 /**
146 * Returns the current setpoint of the PIDController.
147 *
148 * @return The current setpoint.
149 */
150 double GetSetpoint() const;
151
152 /**
153 * Returns true if the error is within the tolerance of the setpoint.
154 *
155 * This will return false until at least one input value has been computed.
156 */
157 bool AtSetpoint() const;
158
159 /**
160 * Enables continuous input.
161 *
162 * Rather then using the max and min input range as constraints, it considers
163 * them to be the same point and automatically calculates the shortest route
164 * to the setpoint.
165 *
166 * @param minimumInput The minimum value expected from the input.
167 * @param maximumInput The maximum value expected from the input.
168 */
169 void EnableContinuousInput(double minimumInput, double maximumInput);
170
171 /**
172 * Disables continuous input.
173 */
175
176 /**
177 * Returns true if continuous input is enabled.
178 */
180
181 /**
182 * Sets the minimum and maximum values for the integrator.
183 *
184 * When the cap is reached, the integrator value is added to the controller
185 * output rather than the integrator value times the integral gain.
186 *
187 * @param minimumIntegral The minimum value of the integrator.
188 * @param maximumIntegral The maximum value of the integrator.
189 */
190 void SetIntegratorRange(double minimumIntegral, double maximumIntegral);
191
192 /**
193 * Sets the error which is considered tolerable for use with AtSetpoint().
194 *
195 * @param positionTolerance Position error which is tolerable.
196 * @param velocityTolerance Velocity error which is tolerable.
197 */
199 double positionTolerance,
200 double velocityTolerance = std::numeric_limits<double>::infinity());
201
202 /**
203 * Returns the difference between the setpoint and the measurement.
204 */
205 double GetPositionError() const;
206
207 /**
208 * Returns the velocity error.
209 */
210 double GetVelocityError() const;
211
212 /**
213 * Returns the next output of the PID controller.
214 *
215 * @param measurement The current measurement of the process variable.
216 */
217 double Calculate(double measurement);
218
219 /**
220 * Returns the next output of the PID controller.
221 *
222 * @param measurement The current measurement of the process variable.
223 * @param setpoint The new setpoint of the controller.
224 */
225 double Calculate(double measurement, double setpoint);
226
227 /**
228 * Reset the previous error, the integral term, and disable the controller.
229 */
230 void Reset();
231
232 void InitSendable(wpi::SendableBuilder& builder) override;
233
234 private:
235 // Factor for "proportional" control
236 double m_Kp;
237
238 // Factor for "integral" control
239 double m_Ki;
240
241 // Factor for "derivative" control
242 double m_Kd;
243
244 // The error range where "integral" control applies
245 double m_iZone = std::numeric_limits<double>::infinity();
246
247 // The period (in seconds) of the control loop running this controller
248 units::second_t m_period;
249
250 double m_maximumIntegral = 1.0;
251
252 double m_minimumIntegral = -1.0;
253
254 double m_maximumInput = 0;
255
256 double m_minimumInput = 0;
257
258 // Do the endpoints wrap around? eg. Absolute encoder
259 bool m_continuous = false;
260
261 // The error at the time of the most recent call to Calculate()
262 double m_positionError = 0;
263 double m_velocityError = 0;
264
265 // The error at the time of the second-most-recent call to Calculate() (used
266 // to compute velocity)
267 double m_prevError = 0;
268
269 // The sum of the errors for use in the integral calc
270 double m_totalError = 0;
271
272 // The error that is considered at setpoint.
273 double m_positionTolerance = 0.05;
274 double m_velocityTolerance = std::numeric_limits<double>::infinity();
275
276 double m_setpoint = 0;
277 double m_measurement = 0;
278
279 bool m_haveSetpoint = false;
280 bool m_haveMeasurement = false;
281};
282
283} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Implements a PID control loop.
Definition: PIDController.h:23
double GetPositionError() const
Returns the difference between the setpoint and the measurement.
double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
PIDController & operator=(const PIDController &)=default
PIDController(const PIDController &)=default
bool IsContinuousInputEnabled() const
Returns true if continuous input is enabled.
units::second_t GetPeriod() const
Gets the period of this controller.
double GetIZone() const
Get the IZone range.
double GetP() const
Gets the proportional coefficient.
PIDController & operator=(PIDController &&)=default
void DisableContinuousInput()
Disables continuous input.
double GetD() const
Gets the differential coefficient.
PIDController(PIDController &&)=default
void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
double Calculate(double measurement, double setpoint)
Returns the next output of the PID controller.
void SetIZone(double iZone)
Sets the IZone range.
void SetP(double Kp)
Sets the proportional coefficient of the PID controller gain.
double Calculate(double measurement)
Returns the next output of the PID controller.
void Reset()
Reset the previous error, the integral term, and disable the controller.
~PIDController() override=default
double GetPositionTolerance() const
Gets the position tolerance of this controller.
double GetI() const
Gets the integral coefficient.
void SetTolerance(double positionTolerance, double velocityTolerance=std::numeric_limits< double >::infinity())
Sets the error which is considered tolerable for use with AtSetpoint().
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
bool AtSetpoint() const
Returns true if the error is within the tolerance of the setpoint.
void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum values for the integrator.
double GetSetpoint() const
Returns the current setpoint of the PIDController.
void SetSetpoint(double setpoint)
Sets the setpoint for the PIDController.
void EnableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.
double GetVelocityError() const
Returns the velocity error.
PIDController(double Kp, double Ki, double Kd, units::second_t period=20_ms)
Allocates a PIDController with the given constants for Kp, Ki, and Kd.
Helper class for building Sendable dashboard representations.
Definition: SendableBuilder.h:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
Definition: AprilTagPoseEstimator.h:15