WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
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 <algorithm>
8#include <cmath>
9#include <limits>
10#include <type_traits>
11
12#include <gcem.hpp>
13#include <wpi/SymbolExports.h>
17
18#include "frc/MathUtil.h"
19#include "units/time.h"
20#include "wpimath/MathShared.h"
21
22namespace frc {
23
24/**
25 * Implements a PID control loop.
26 */
28 : public wpi::Sendable,
29 public wpi::SendableHelper<PIDController> {
30 public:
31 /**
32 * Allocates a PIDController with the given constants for Kp, Ki, and Kd.
33 *
34 * @param Kp The proportional coefficient. Must be >= 0.
35 * @param Ki The integral coefficient. Must be >= 0.
36 * @param Kd The derivative coefficient. Must be >= 0.
37 * @param period The period between controller updates in seconds. The
38 * default is 20 milliseconds. Must be positive.
39 */
40 constexpr PIDController(double Kp, double Ki, double Kd,
41 units::second_t period = 20_ms)
42 : m_Kp(Kp), m_Ki(Ki), m_Kd(Kd), m_period(period) {
43 bool invalidGains = false;
44 if (Kp < 0.0) {
46 "Kp must be a non-negative number, got {}!", Kp);
47 invalidGains = true;
48 }
49 if (Ki < 0.0) {
51 "Ki must be a non-negative number, got {}!", Ki);
52 invalidGains = true;
53 }
54 if (Kd < 0.0) {
56 "Kd must be a non-negative number, got {}!", Kd);
57 invalidGains = true;
58 }
59 if (invalidGains) {
60 m_Kp = 0.0;
61 m_Ki = 0.0;
62 m_Kd = 0.0;
63 wpi::math::MathSharedStore::ReportWarning("PID gains defaulted to 0.");
64 }
65
66 if (period <= 0_s) {
68 "Controller period must be a positive number, got {}!",
69 period.value());
70 m_period = 20_ms;
72 "Controller period defaulted to 20ms.");
73 }
74 if (!std::is_constant_evaluated()) {
75 ++instances;
76
79 wpi::SendableRegistry::Add(this, "PIDController", instances);
80 }
81 }
82
83 constexpr ~PIDController() override = default;
84
85 constexpr PIDController(const PIDController&) = default;
86 constexpr PIDController& operator=(const PIDController&) = default;
87 constexpr PIDController(PIDController&&) = default;
88 constexpr PIDController& operator=(PIDController&&) = default;
89
90 /**
91 * Sets the PID Controller gain parameters.
92 *
93 * Sets the proportional, integral, and differential coefficients.
94 *
95 * @param Kp The proportional coefficient. Must be >= 0.
96 * @param Ki The integral coefficient. Must be >= 0.
97 * @param Kd The differential coefficient. Must be >= 0.
98 */
99 constexpr void SetPID(double Kp, double Ki, double Kd) {
100 m_Kp = Kp;
101 m_Ki = Ki;
102 m_Kd = Kd;
103 }
104
105 /**
106 * Sets the proportional coefficient of the PID controller gain.
107 *
108 * @param Kp The proportional coefficient. Must be >= 0.
109 */
110 constexpr void SetP(double Kp) { m_Kp = Kp; }
111
112 /**
113 * Sets the integral coefficient of the PID controller gain.
114 *
115 * @param Ki The integral coefficient. Must be >= 0.
116 */
117 constexpr void SetI(double Ki) { m_Ki = Ki; }
118
119 /**
120 * Sets the differential coefficient of the PID controller gain.
121 *
122 * @param Kd The differential coefficient. Must be >= 0.
123 */
124 constexpr void SetD(double Kd) { m_Kd = Kd; }
125
126 /**
127 * Sets the IZone range. When the absolute value of the position error is
128 * greater than IZone, the total accumulated error will reset to zero,
129 * disabling integral gain until the absolute value of the position error is
130 * less than IZone. This is used to prevent integral windup. Must be
131 * non-negative. Passing a value of zero will effectively disable integral
132 * gain. Passing a value of infinity disables IZone functionality.
133 *
134 * @param iZone Maximum magnitude of error to allow integral control. Must be
135 * >= 0.
136 */
137 constexpr void SetIZone(double iZone) {
138 if (std::is_constant_evaluated() && iZone < 0) {
140 "IZone must be a non-negative number, got {}!", iZone);
141 }
142 m_iZone = iZone;
143 }
144
145 /**
146 * Gets the proportional coefficient.
147 *
148 * @return proportional coefficient
149 */
150 constexpr double GetP() const { return m_Kp; }
151
152 /**
153 * Gets the integral coefficient.
154 *
155 * @return integral coefficient
156 */
157 constexpr double GetI() const { return m_Ki; }
158
159 /**
160 * Gets the differential coefficient.
161 *
162 * @return differential coefficient
163 */
164 constexpr double GetD() const { return m_Kd; }
165
166 /**
167 * Get the IZone range.
168 *
169 * @return Maximum magnitude of error to allow integral control.
170 */
171 constexpr double GetIZone() const { return m_iZone; }
172
173 /**
174 * Gets the period of this controller.
175 *
176 * @return The period of the controller.
177 */
178 constexpr units::second_t GetPeriod() const { return m_period; }
179
180 /**
181 * Gets the error tolerance of this controller. Defaults to 0.05.
182 *
183 * @return The error tolerance of the controller.
184 */
185 constexpr double GetErrorTolerance() const { return m_errorTolerance; }
186
187 /**
188 * Gets the error derivative tolerance of this controller. Defaults to ∞.
189 *
190 * @return The error derivative tolerance of the controller.
191 */
192 constexpr double GetErrorDerivativeTolerance() const {
193 return m_errorDerivativeTolerance;
194 }
195
196 /**
197 * Gets the position tolerance of this controller.
198 *
199 * @return The position tolerance of the controller.
200 * @deprecated Use GetErrorTolerance() instead.
201 */
202 [[deprecated("Use the GetErrorTolerance method instead.")]]
203 constexpr double GetPositionTolerance() const {
204 return m_errorTolerance;
205 }
206
207 /**
208 * Gets the velocity tolerance of this controller.
209 *
210 * @return The velocity tolerance of the controller.
211 * @deprecated Use GetErrorDerivativeTolerance() instead.
212 */
213 [[deprecated("Use the GetErrorDerivativeTolerance method instead.")]]
214 constexpr double GetVelocityTolerance() const {
215 return m_errorDerivativeTolerance;
216 }
217
218 /**
219 * Gets the accumulated error used in the integral calculation of this
220 * controller.
221 *
222 * @return The accumulated error of this controller.
223 */
224 constexpr double GetAccumulatedError() const { return m_totalError; }
225
226 /**
227 * Sets the setpoint for the PIDController.
228 *
229 * @param setpoint The desired setpoint.
230 */
231 constexpr void SetSetpoint(double setpoint) {
232 m_setpoint = setpoint;
233 m_haveSetpoint = true;
234
235 if (m_continuous) {
236 double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
237 m_error =
238 InputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
239 } else {
240 m_error = m_setpoint - m_measurement;
241 }
242
243 m_errorDerivative = (m_error - m_prevError) / m_period.value();
244 }
245
246 /**
247 * Returns the current setpoint of the PIDController.
248 *
249 * @return The current setpoint.
250 */
251 constexpr double GetSetpoint() const { return m_setpoint; }
252
253 /**
254 * Returns true if the error is within the tolerance of the setpoint.
255 * The error tolerance defauls to 0.05, and the error derivative tolerance
256 * defaults to ∞.
257 *
258 * This will return false until at least one input value has been computed.
259 */
260 constexpr bool AtSetpoint() const {
261 return m_haveMeasurement && m_haveSetpoint &&
262 gcem::abs(m_error) < m_errorTolerance &&
263 gcem::abs(m_errorDerivative) < m_errorDerivativeTolerance;
264 }
265
266 /**
267 * Enables continuous input.
268 *
269 * Rather then using the max and min input range as constraints, it considers
270 * them to be the same point and automatically calculates the shortest route
271 * to the setpoint.
272 *
273 * @param minimumInput The minimum value expected from the input.
274 * @param maximumInput The maximum value expected from the input.
275 */
276 constexpr void EnableContinuousInput(double minimumInput,
277 double maximumInput) {
278 m_continuous = true;
279 m_minimumInput = minimumInput;
280 m_maximumInput = maximumInput;
281 }
282
283 /**
284 * Disables continuous input.
285 */
286 constexpr void DisableContinuousInput() { m_continuous = false; }
287
288 /**
289 * Returns true if continuous input is enabled.
290 */
291 constexpr bool IsContinuousInputEnabled() const { return m_continuous; }
292
293 /**
294 * Sets the minimum and maximum contributions of the integral term.
295 *
296 * The internal integrator is clamped so that the integral term's contribution
297 * to the output stays between minimumIntegral and maximumIntegral. This
298 * prevents integral windup.
299 *
300 * @param minimumIntegral The minimum contribution of the integral term.
301 * @param maximumIntegral The maximum contribution of the integral term.
302 */
303 constexpr void SetIntegratorRange(double minimumIntegral,
304 double maximumIntegral) {
305 m_minimumIntegral = minimumIntegral;
306 m_maximumIntegral = maximumIntegral;
307 }
308
309 /**
310 * Sets the error which is considered tolerable for use with AtSetpoint().
311 *
312 * @param errorTolerance error which is tolerable.
313 * @param errorDerivativeTolerance error derivative which is tolerable.
314 */
315 constexpr void SetTolerance(double errorTolerance,
316 double errorDerivativeTolerance =
317 std::numeric_limits<double>::infinity()) {
318 m_errorTolerance = errorTolerance;
319 m_errorDerivativeTolerance = errorDerivativeTolerance;
320 }
321
322 /**
323 * Returns the difference between the setpoint and the measurement.
324 */
325 constexpr double GetError() const { return m_error; }
326
327 /**
328 * Returns the error derivative.
329 */
330 constexpr double GetErrorDerivative() const { return m_errorDerivative; }
331
332 /**
333 * Returns the difference between the setpoint and the measurement.
334 * @deprecated Use GetError() instead.
335 */
336 [[deprecated("Use GetError method instead.")]]
337 constexpr double GetPositionError() const {
338 return m_error;
339 }
340
341 /**
342 * Returns the velocity error.
343 * @deprecated Use GetErrorDerivative() instead.
344 */
345 [[deprecated("Use GetErrorDerivative method instead.")]]
346 constexpr double GetVelocityError() const {
347 return m_errorDerivative;
348 }
349
350 /**
351 * Returns the next output of the PID controller.
352 *
353 * @param measurement The current measurement of the process variable.
354 */
355 constexpr double Calculate(double measurement) {
356 m_measurement = measurement;
357 m_prevError = m_error;
358 m_haveMeasurement = true;
359
360 if (m_continuous) {
361 double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
362 m_error =
363 InputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
364 } else {
365 m_error = m_setpoint - m_measurement;
366 }
367
368 m_errorDerivative = (m_error - m_prevError) / m_period.value();
369
370 // If the absolute value of the position error is outside of IZone, reset
371 // the total error
372 if (gcem::abs(m_error) > m_iZone) {
373 m_totalError = 0;
374 } else if (m_Ki != 0) {
375 m_totalError =
376 std::clamp(m_totalError + m_error * m_period.value(),
377 m_minimumIntegral / m_Ki, m_maximumIntegral / m_Ki);
378 }
379
380 return m_Kp * m_error + m_Ki * m_totalError + m_Kd * m_errorDerivative;
381 }
382
383 /**
384 * Returns the next output of the PID controller.
385 *
386 * @param measurement The current measurement of the process variable.
387 * @param setpoint The new setpoint of the controller.
388 */
389 constexpr double Calculate(double measurement, double setpoint) {
390 m_setpoint = setpoint;
391 m_haveSetpoint = true;
392 return Calculate(measurement);
393 }
394
395 /**
396 * Reset the previous error, the integral term, and disable the controller.
397 */
398 constexpr void Reset() {
399 m_error = 0;
400 m_prevError = 0;
401 m_totalError = 0;
402 m_errorDerivative = 0;
403 m_haveMeasurement = false;
404 }
405
406 void InitSendable(wpi::SendableBuilder& builder) override;
407
408 private:
409 // Factor for "proportional" control
410 double m_Kp;
411
412 // Factor for "integral" control
413 double m_Ki;
414
415 // Factor for "derivative" control
416 double m_Kd;
417
418 // The error range where "integral" control applies
419 double m_iZone = std::numeric_limits<double>::infinity();
420
421 // The period (in seconds) of the control loop running this controller
422 units::second_t m_period;
423
424 double m_maximumIntegral = 1.0;
425
426 double m_minimumIntegral = -1.0;
427
428 double m_maximumInput = 0;
429
430 double m_minimumInput = 0;
431
432 // Do the endpoints wrap around? eg. Absolute encoder
433 bool m_continuous = false;
434
435 // The error at the time of the most recent call to Calculate()
436 double m_error = 0;
437 double m_errorDerivative = 0;
438
439 // The error at the time of the second-most-recent call to Calculate() (used
440 // to compute velocity)
441 double m_prevError = 0;
442
443 // The sum of the errors for use in the integral calc
444 double m_totalError = 0;
445
446 // The error that is considered at setpoint.
447 double m_errorTolerance = 0.05;
448 double m_errorDerivativeTolerance = std::numeric_limits<double>::infinity();
449
450 double m_setpoint = 0;
451 double m_measurement = 0;
452
453 bool m_haveSetpoint = false;
454 bool m_haveMeasurement = false;
455
456 // Usage reporting instances
457 inline static int instances = 0;
458};
459
460} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Implements a PID control loop.
Definition PIDController.h:29
constexpr bool IsContinuousInputEnabled() const
Returns true if continuous input is enabled.
Definition PIDController.h:291
constexpr units::second_t GetPeriod() const
Gets the period of this controller.
Definition PIDController.h:178
constexpr PIDController(PIDController &&)=default
constexpr double Calculate(double measurement)
Returns the next output of the PID controller.
Definition PIDController.h:355
constexpr double GetErrorDerivativeTolerance() const
Gets the error derivative tolerance of this controller.
Definition PIDController.h:192
constexpr double GetI() const
Gets the integral coefficient.
Definition PIDController.h:157
constexpr void EnableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.
Definition PIDController.h:276
constexpr double GetD() const
Gets the differential coefficient.
Definition PIDController.h:164
constexpr void DisableContinuousInput()
Disables continuous input.
Definition PIDController.h:286
constexpr bool AtSetpoint() const
Returns true if the error is within the tolerance of the setpoint.
Definition PIDController.h:260
constexpr void SetTolerance(double errorTolerance, double errorDerivativeTolerance=std::numeric_limits< double >::infinity())
Sets the error which is considered tolerable for use with AtSetpoint().
Definition PIDController.h:315
constexpr double GetVelocityError() const
Returns the velocity error.
Definition PIDController.h:346
constexpr 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.
Definition PIDController.h:40
constexpr double GetPositionTolerance() const
Gets the position tolerance of this controller.
Definition PIDController.h:203
constexpr void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
Definition PIDController.h:124
constexpr void SetIZone(double iZone)
Sets the IZone range.
Definition PIDController.h:137
constexpr double GetErrorTolerance() const
Gets the error tolerance of this controller.
Definition PIDController.h:185
constexpr double GetP() const
Gets the proportional coefficient.
Definition PIDController.h:150
constexpr PIDController & operator=(PIDController &&)=default
constexpr PIDController(const PIDController &)=default
constexpr void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum contributions of the integral term.
Definition PIDController.h:303
constexpr double GetAccumulatedError() const
Gets the accumulated error used in the integral calculation of this controller.
Definition PIDController.h:224
constexpr void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
Definition PIDController.h:99
constexpr double Calculate(double measurement, double setpoint)
Returns the next output of the PID controller.
Definition PIDController.h:389
constexpr void Reset()
Reset the previous error, the integral term, and disable the controller.
Definition PIDController.h:398
constexpr void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
Definition PIDController.h:117
constexpr PIDController & operator=(const PIDController &)=default
constexpr void SetP(double Kp)
Sets the proportional coefficient of the PID controller gain.
Definition PIDController.h:110
constexpr double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
Definition PIDController.h:214
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
constexpr double GetErrorDerivative() const
Returns the error derivative.
Definition PIDController.h:330
constexpr ~PIDController() override=default
constexpr void SetSetpoint(double setpoint)
Sets the setpoint for the PIDController.
Definition PIDController.h:231
constexpr double GetError() const
Returns the difference between the setpoint and the measurement.
Definition PIDController.h:325
constexpr double GetIZone() const
Get the IZone range.
Definition PIDController.h:171
constexpr double GetSetpoint() const
Returns the current setpoint of the PIDController.
Definition PIDController.h:251
constexpr double GetPositionError() const
Returns the difference between the setpoint and the measurement.
Definition PIDController.h:337
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:21
Interface for Sendable objects.
Definition Sendable.h:16
static void Add(Sendable *sendable, std::string_view name)
Adds an object to the registry.
static void ReportError(const S &format, Args &&... args)
Definition MathShared.h:62
static void ReportUsage(MathUsageId id, int count)
Definition MathShared.h:75
static void ReportWarning(const S &format, Args &&... args)
Definition MathShared.h:71
Definition CAN.h:11
constexpr T InputModulus(T input, T minimumInput, T maximumInput)
Returns modulus of input.
Definition MathUtil.h:95
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition abs.hpp:40