WPILibC++ 2023.4.3-108-ge5452e3
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 frc2 {
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.
29 * @param Ki The integral coefficient.
30 * @param Kd The derivative coefficient.
31 * @param period The period between controller updates in seconds. The
32 * default is 20 milliseconds. Must be non-zero and 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 Proportional coefficient
50 * @param Ki Integral coefficient
51 * @param Kd Differential coefficient
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 proportional coefficient
59 */
60 void SetP(double Kp);
61
62 /**
63 * Sets the integral coefficient of the PID controller gain.
64 *
65 * @param Ki integral coefficient
66 */
67 void SetI(double Ki);
68
69 /**
70 * Sets the differential coefficient of the PID controller gain.
71 *
72 * @param Kd differential coefficient
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.
85 */
86 void SetIZone(double iZone);
87
88 /**
89 * Gets the proportional coefficient.
90 *
91 * @return proportional coefficient
92 */
93 double GetP() const;
94
95 /**
96 * Gets the integral coefficient.
97 *
98 * @return integral coefficient
99 */
100 double GetI() const;
101
102 /**
103 * Gets the differential coefficient.
104 *
105 * @return differential coefficient
106 */
107 double GetD() const;
108
109 /**
110 * Get the IZone range.
111 *
112 * @return Maximum magnitude of error to allow integral control.
113 */
114 double GetIZone() const;
115
116 /**
117 * Gets the period of this controller.
118 *
119 * @return The period of the controller.
120 */
121 units::second_t GetPeriod() const;
122
123 /**
124 * Gets the position tolerance of this controller.
125 *
126 * @return The position tolerance of the controller.
127 */
128 double GetPositionTolerance() const;
129
130 /**
131 * Gets the velocity tolerance of this controller.
132 *
133 * @return The velocity tolerance of the controller.
134 */
135 double GetVelocityTolerance() const;
136
137 /**
138 * Sets the setpoint for the PIDController.
139 *
140 * @param setpoint The desired setpoint.
141 */
142 void SetSetpoint(double setpoint);
143
144 /**
145 * Returns the current setpoint of the PIDController.
146 *
147 * @return The current setpoint.
148 */
149 double GetSetpoint() const;
150
151 /**
152 * Returns true if the error is within the tolerance of the setpoint.
153 *
154 * This will return false until at least one input value has been computed.
155 */
156 bool AtSetpoint() const;
157
158 /**
159 * Enables continuous input.
160 *
161 * Rather then using the max and min input range as constraints, it considers
162 * them to be the same point and automatically calculates the shortest route
163 * to the setpoint.
164 *
165 * @param minimumInput The minimum value expected from the input.
166 * @param maximumInput The maximum value expected from the input.
167 */
168 void EnableContinuousInput(double minimumInput, double maximumInput);
169
170 /**
171 * Disables continuous input.
172 */
174
175 /**
176 * Returns true if continuous input is enabled.
177 */
179
180 /**
181 * Sets the minimum and maximum values for the integrator.
182 *
183 * When the cap is reached, the integrator value is added to the controller
184 * output rather than the integrator value times the integral gain.
185 *
186 * @param minimumIntegral The minimum value of the integrator.
187 * @param maximumIntegral The maximum value of the integrator.
188 */
189 void SetIntegratorRange(double minimumIntegral, double maximumIntegral);
190
191 /**
192 * Sets the error which is considered tolerable for use with AtSetpoint().
193 *
194 * @param positionTolerance Position error which is tolerable.
195 * @param velocityTolerance Velocity error which is tolerable.
196 */
198 double positionTolerance,
199 double velocityTolerance = std::numeric_limits<double>::infinity());
200
201 /**
202 * Returns the difference between the setpoint and the measurement.
203 */
204 double GetPositionError() const;
205
206 /**
207 * Returns the velocity error.
208 */
209 double GetVelocityError() const;
210
211 /**
212 * Returns the next output of the PID controller.
213 *
214 * @param measurement The current measurement of the process variable.
215 */
216 double Calculate(double measurement);
217
218 /**
219 * Returns the next output of the PID controller.
220 *
221 * @param measurement The current measurement of the process variable.
222 * @param setpoint The new setpoint of the controller.
223 */
224 double Calculate(double measurement, double setpoint);
225
226 /**
227 * Reset the previous error, the integral term, and disable the controller.
228 */
229 void Reset();
230
231 void InitSendable(wpi::SendableBuilder& builder) override;
232
233 private:
234 // Factor for "proportional" control
235 double m_Kp;
236
237 // Factor for "integral" control
238 double m_Ki;
239
240 // Factor for "derivative" control
241 double m_Kd;
242
243 // The error range where "integral" control applies
244 double m_iZone = std::numeric_limits<double>::infinity();
245
246 // The period (in seconds) of the control loop running this controller
247 units::second_t m_period;
248
249 double m_maximumIntegral = 1.0;
250
251 double m_minimumIntegral = -1.0;
252
253 double m_maximumInput = 0;
254
255 double m_minimumInput = 0;
256
257 // Do the endpoints wrap around? eg. Absolute encoder
258 bool m_continuous = false;
259
260 // The error at the time of the most recent call to Calculate()
261 double m_positionError = 0;
262 double m_velocityError = 0;
263
264 // The error at the time of the second-most-recent call to Calculate() (used
265 // to compute velocity)
266 double m_prevError = 0;
267
268 // The sum of the errors for use in the integral calc
269 double m_totalError = 0;
270
271 // The error that is considered at setpoint.
272 double m_positionTolerance = 0.05;
273 double m_velocityTolerance = std::numeric_limits<double>::infinity();
274
275 double m_setpoint = 0;
276 double m_measurement = 0;
277
278 bool m_haveSetpoint = false;
279 bool m_haveMeasurement = false;
280};
281
282} // namespace frc2
283
284namespace frc {
285
287
288} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Implements a PID control loop.
Definition: PIDController.h:23
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.
double GetIZone() const
Get the IZone range.
void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
double GetP() const
Gets the proportional coefficient.
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
void SetTolerance(double positionTolerance, double velocityTolerance=std::numeric_limits< double >::infinity())
Sets the error which is considered tolerable for use with AtSetpoint().
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.
bool AtSetpoint() const
Returns true if the error is within the tolerance of the setpoint.
double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
double GetPositionTolerance() const
Gets the position tolerance of this controller.
double GetI() const
Gets the integral coefficient.
void DisableContinuousInput()
Disables continuous input.
double GetD() const
Gets the differential coefficient.
void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
double GetPositionError() const
Returns the difference between the setpoint and the measurement.
double GetSetpoint() const
Returns the current setpoint of the PIDController.
PIDController(const PIDController &)=default
void SetIZone(double iZone)
Sets the IZone range.
void SetSetpoint(double setpoint)
Sets the setpoint for the PIDController.
void EnableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.
void Reset()
Reset the previous error, the integral term, and disable the controller.
double GetVelocityError() const
Returns the velocity error.
units::second_t GetPeriod() const
Gets the period of this controller.
PIDController & operator=(const PIDController &)=default
double Calculate(double measurement, double setpoint)
Returns the next output of the PID controller.
~PIDController() override=default
void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum values for the integrator.
PIDController(PIDController &&)=default
PIDController & operator=(PIDController &&)=default
bool IsContinuousInputEnabled() const
Returns true if continuous input is enabled.
Definition: SendableBuilder.h:18
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: ProfiledPIDCommand.h:18
Definition: AprilTagPoseEstimator.h:15