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