WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
ProfiledPIDController.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 <limits>
8#include <type_traits>
9
13#include "wpi/units/time.hpp"
18
19namespace wpi::math {
24
25/**
26 * Implements a PID control loop whose setpoint is constrained by a trapezoid
27 * profile.
28 */
29template <class Distance>
31 : public wpi::util::Sendable,
32 public wpi::util::SendableHelper<ProfiledPIDController<Distance>> {
33 public:
34 using Distance_t = wpi::units::unit_t<Distance>;
35 using Velocity =
36 wpi::units::compound_unit<Distance,
37 wpi::units::inverse<wpi::units::seconds>>;
38 using Velocity_t = wpi::units::unit_t<Velocity>;
40 wpi::units::compound_unit<Velocity,
41 wpi::units::inverse<wpi::units::seconds>>;
42 using Acceleration_t = wpi::units::unit_t<Acceleration>;
45
46 /**
47 * Allocates a ProfiledPIDController with the given constants for Kp, Ki, and
48 * Kd. Users should call reset() when they first start running the controller
49 * to avoid unwanted behavior.
50 *
51 * @param Kp The proportional coefficient. Must be >= 0.
52 * @param Ki The integral coefficient. Must be >= 0.
53 * @param Kd The derivative coefficient. Must be >= 0.
54 * @param constraints Velocity and acceleration constraints for goal.
55 * @param period The period between controller updates in seconds. The
56 * default is 20 milliseconds. Must be positive.
57 */
58 constexpr ProfiledPIDController(double Kp, double Ki, double Kd,
59 Constraints constraints,
60 wpi::units::second_t period = 20_ms)
61 : m_controller{Kp, Ki, Kd, period},
62 m_constraints{constraints},
63 m_profile{m_constraints} {
64 if (!std::is_constant_evaluated()) {
66 wpi::math::MathSharedStore::ReportUsage("ProfiledPIDController",
67 std::to_string(instances));
68 wpi::util::SendableRegistry::Add(this, "ProfiledPIDController",
69 instances);
70 }
71 }
72
73 constexpr ~ProfiledPIDController() override = default;
74
75 constexpr ProfiledPIDController(const ProfiledPIDController&) = default;
77 default;
80
81 /**
82 * Sets the PID Controller gain parameters.
83 *
84 * Sets the proportional, integral, and differential coefficients.
85 *
86 * @param Kp The proportional coefficient. Must be >= 0.
87 * @param Ki The integral coefficient. Must be >= 0.
88 * @param Kd The differential coefficient. Must be >= 0.
89 */
90 constexpr void SetPID(double Kp, double Ki, double Kd) {
91 m_controller.SetPID(Kp, Ki, Kd);
92 }
93
94 /**
95 * Sets the proportional coefficient of the PID controller gain.
96 *
97 * @param Kp The proportional coefficient. Must be >= 0.
98 */
99 constexpr void SetP(double Kp) { m_controller.SetP(Kp); }
100
101 /**
102 * Sets the integral coefficient of the PID controller gain.
103 *
104 * @param Ki The integral coefficient. Must be >= 0.
105 */
106 constexpr void SetI(double Ki) { m_controller.SetI(Ki); }
107
108 /**
109 * Sets the differential coefficient of the PID controller gain.
110 *
111 * @param Kd The differential coefficient. Must be >= 0.
112 */
113 constexpr void SetD(double Kd) { m_controller.SetD(Kd); }
114
115 /**
116 * Sets the IZone range. When the absolute value of the position error is
117 * greater than IZone, the total accumulated error will reset to zero,
118 * disabling integral gain until the absolute value of the position error is
119 * less than IZone. This is used to prevent integral windup. Must be
120 * non-negative. Passing a value of zero will effectively disable integral
121 * gain. Passing a value of infinity disables IZone functionality.
122 *
123 * @param iZone Maximum magnitude of error to allow integral control. Must be
124 * >= 0.
125 */
126 constexpr void SetIZone(double iZone) { m_controller.SetIZone(iZone); }
127
128 /**
129 * Gets the proportional coefficient.
130 *
131 * @return proportional coefficient
132 */
133 constexpr double GetP() const { return m_controller.GetP(); }
134
135 /**
136 * Gets the integral coefficient.
137 *
138 * @return integral coefficient
139 */
140 constexpr double GetI() const { return m_controller.GetI(); }
141
142 /**
143 * Gets the differential coefficient.
144 *
145 * @return differential coefficient
146 */
147 constexpr double GetD() const { return m_controller.GetD(); }
148
149 /**
150 * Get the IZone range.
151 *
152 * @return Maximum magnitude of error to allow integral control.
153 */
154 constexpr double GetIZone() const { return m_controller.GetIZone(); }
155
156 /**
157 * Gets the period of this controller.
158 *
159 * @return The period of the controller.
160 */
161 constexpr wpi::units::second_t GetPeriod() const {
162 return m_controller.GetPeriod();
163 }
164
165 /**
166 * Gets the position tolerance of this controller.
167 *
168 * @return The position tolerance of the controller.
169 */
170 constexpr double GetPositionTolerance() const {
171 return m_controller.GetErrorTolerance();
172 }
173
174 /**
175 * Gets the velocity tolerance of this controller.
176 *
177 * @return The velocity tolerance of the controller.
178 */
179 constexpr double GetVelocityTolerance() const {
180 return m_controller.GetErrorDerivativeTolerance();
181 }
182
183 /**
184 * Gets the accumulated error used in the integral calculation of this
185 * controller.
186 *
187 * @return The accumulated error of this controller.
188 */
189 constexpr double GetAccumulatedError() const {
190 return m_controller.GetAccumulatedError();
191 }
192
193 /**
194 * Sets the goal for the ProfiledPIDController.
195 *
196 * @param goal The desired unprofiled setpoint.
197 */
198 constexpr void SetGoal(State goal) { m_goal = goal; }
199
200 /**
201 * Sets the goal for the ProfiledPIDController.
202 *
203 * @param goal The desired unprofiled setpoint.
204 */
205 constexpr void SetGoal(Distance_t goal) { m_goal = {goal, Velocity_t{0}}; }
206
207 /**
208 * Gets the goal for the ProfiledPIDController.
209 */
210 constexpr State GetGoal() const { return m_goal; }
211
212 /**
213 * Returns true if the error is within the tolerance of the error.
214 *
215 * This will return false until at least one input value has been computed.
216 */
217 constexpr bool AtGoal() const { return AtSetpoint() && m_goal == m_setpoint; }
218
219 /**
220 * Set velocity and acceleration constraints for goal.
221 *
222 * @param constraints Velocity and acceleration constraints for goal.
223 */
224 constexpr void SetConstraints(Constraints constraints) {
225 m_constraints = constraints;
226 m_profile = TrapezoidProfile<Distance>{m_constraints};
227 }
228
229 /**
230 * Get the velocity and acceleration constraints for this controller.
231 * @return Velocity and acceleration constraints.
232 */
233 constexpr Constraints GetConstraints() { return m_constraints; }
234
235 /**
236 * Returns the current setpoint of the ProfiledPIDController.
237 *
238 * @return The current setpoint.
239 */
240 constexpr State GetSetpoint() const { return m_setpoint; }
241
242 /**
243 * Returns true if the error is within the tolerance of the error.
244 *
245 * Currently this just reports on target as the actual value passes through
246 * the setpoint. Ideally it should be based on being within the tolerance for
247 * some period of time.
248 *
249 * This will return false until at least one input value has been computed.
250 */
251 constexpr bool AtSetpoint() const { return m_controller.AtSetpoint(); }
252
253 /**
254 * Enables continuous input.
255 *
256 * Rather then using the max and min input range as constraints, it considers
257 * them to be the same point and automatically calculates the shortest route
258 * to the setpoint.
259 *
260 * @param minimumInput The minimum value expected from the input.
261 * @param maximumInput The maximum value expected from the input.
262 */
263 constexpr void EnableContinuousInput(Distance_t minimumInput,
264 Distance_t maximumInput) {
265 m_controller.EnableContinuousInput(minimumInput.value(),
266 maximumInput.value());
267 m_minimumInput = minimumInput;
268 m_maximumInput = maximumInput;
269 }
270
271 /**
272 * Disables continuous input.
273 */
274 constexpr void DisableContinuousInput() {
275 m_controller.DisableContinuousInput();
276 }
277
278 /**
279 * Sets the minimum and maximum contributions of the integral term.
280 *
281 * The internal integrator is clamped so that the integral term's contribution
282 * to the output stays between minimumIntegral and maximumIntegral. This
283 * prevents integral windup.
284 *
285 * @param minimumIntegral The minimum contribution of the integral term.
286 * @param maximumIntegral The maximum contribution of the integral term.
287 */
288 constexpr void SetIntegratorRange(double minimumIntegral,
289 double maximumIntegral) {
290 m_controller.SetIntegratorRange(minimumIntegral, maximumIntegral);
291 }
292
293 /**
294 * Sets the error which is considered tolerable for use with
295 * AtSetpoint().
296 *
297 * @param positionTolerance Position error which is tolerable.
298 * @param velocityTolerance Velocity error which is tolerable.
299 */
300 constexpr void SetTolerance(Distance_t positionTolerance,
301 Velocity_t velocityTolerance = Velocity_t{
302 std::numeric_limits<double>::infinity()}) {
303 m_controller.SetTolerance(positionTolerance.value(),
304 velocityTolerance.value());
305 }
306
307 /**
308 * Returns the difference between the setpoint and the measurement.
309 *
310 * @return The error.
311 */
312 constexpr Distance_t GetPositionError() const {
313 return Distance_t{m_controller.GetError()};
314 }
315
316 /**
317 * Returns the change in error per second.
318 */
319 constexpr Velocity_t GetVelocityError() const {
320 return Velocity_t{m_controller.GetErrorDerivative()};
321 }
322
323 /**
324 * Returns the next output of the PID controller.
325 *
326 * @param measurement The current measurement of the process variable.
327 */
328 constexpr double Calculate(Distance_t measurement) {
329 if (m_controller.IsContinuousInputEnabled()) {
330 // Get error which is smallest distance between goal and measurement
331 auto errorBound = (m_maximumInput - m_minimumInput) / 2.0;
332 auto goalMinDistance = wpi::math::InputModulus<Distance_t>(
333 m_goal.position - measurement, -errorBound, errorBound);
334 auto setpointMinDistance = wpi::math::InputModulus<Distance_t>(
335 m_setpoint.position - measurement, -errorBound, errorBound);
336
337 // Recompute the profile goal with the smallest error, thus giving the
338 // shortest path. The goal may be outside the input range after this
339 // operation, but that's OK because the controller will still go there and
340 // report an error of zero. In other words, the setpoint only needs to be
341 // offset from the measurement by the input range modulus; they don't need
342 // to be equal.
343 m_goal.position = goalMinDistance + measurement;
344 m_setpoint.position = setpointMinDistance + measurement;
345 }
346
347 m_setpoint = m_profile.Calculate(GetPeriod(), m_setpoint, m_goal);
348 return m_controller.Calculate(measurement.value(),
349 m_setpoint.position.value());
350 }
351
352 /**
353 * Returns the next output of the PID controller.
354 *
355 * @param measurement The current measurement of the process variable.
356 * @param goal The new goal of the controller.
357 */
358 constexpr double Calculate(Distance_t measurement, State goal) {
359 SetGoal(goal);
360 return Calculate(measurement);
361 }
362 /**
363 * Returns the next output of the PID controller.
364 *
365 * @param measurement The current measurement of the process variable.
366 * @param goal The new goal of the controller.
367 */
368 constexpr double Calculate(Distance_t measurement, Distance_t goal) {
369 SetGoal(goal);
370 return Calculate(measurement);
371 }
372
373 /**
374 * Returns the next output of the PID controller.
375 *
376 * @param measurement The current measurement of the process variable.
377 * @param goal The new goal of the controller.
378 * @param constraints Velocity and acceleration constraints for goal.
379 */
380 constexpr double Calculate(
381 Distance_t measurement, Distance_t goal,
383 SetConstraints(constraints);
384 return Calculate(measurement, goal);
385 }
386
387 /**
388 * Reset the previous error and the integral term.
389 *
390 * @param measurement The current measured State of the system.
391 */
392 constexpr void Reset(const State& measurement) {
393 m_controller.Reset();
394 m_setpoint = measurement;
395 }
396
397 /**
398 * Reset the previous error and the integral term.
399 *
400 * @param measuredPosition The current measured position of the system.
401 * @param measuredVelocity The current measured velocity of the system.
402 */
403 constexpr void Reset(Distance_t measuredPosition,
404 Velocity_t measuredVelocity) {
405 Reset(State{measuredPosition, measuredVelocity});
406 }
407
408 /**
409 * Reset the previous error and the integral term.
410 *
411 * @param measuredPosition The current measured position of the system. The
412 * velocity is assumed to be zero.
413 */
414 constexpr void Reset(Distance_t measuredPosition) {
415 Reset(measuredPosition, Velocity_t{0});
416 }
417
418 void InitSendable(wpi::util::SendableBuilder& builder) override {
419 builder.SetSmartDashboardType("ProfiledPIDController");
420 builder.AddDoubleProperty(
421 "p", [this] { return GetP(); }, [this](double value) { SetP(value); });
422 builder.AddDoubleProperty(
423 "i", [this] { return GetI(); }, [this](double value) { SetI(value); });
424 builder.AddDoubleProperty(
425 "d", [this] { return GetD(); }, [this](double value) { SetD(value); });
426 builder.AddDoubleProperty(
427 "izone", [this] { return GetIZone(); },
428 [this](double value) { SetIZone(value); });
429 builder.AddDoubleProperty(
430 "maxVelocity", [this] { return GetConstraints().maxVelocity.value(); },
431 [this](double value) {
433 Constraints{Velocity_t{value}, GetConstraints().maxAcceleration});
434 });
435 builder.AddDoubleProperty(
436 "maxAcceleration",
437 [this] { return GetConstraints().maxAcceleration.value(); },
438 [this](double value) {
440 Constraints{GetConstraints().maxVelocity, Acceleration_t{value}});
441 });
442 builder.AddDoubleProperty(
443 "goal", [this] { return GetGoal().position.value(); },
444 [this](double value) { SetGoal(Distance_t{value}); });
445 }
446
447 private:
448 PIDController m_controller;
449 Distance_t m_minimumInput{0};
450 Distance_t m_maximumInput{0};
451
453 TrapezoidProfile<Distance> m_profile;
456};
457
458} // 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
Implements a PID control loop.
Definition PIDController.hpp:28
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:314
constexpr void SetP(double Kp)
Sets the proportional coefficient of the PID controller gain.
Definition ProfiledPIDController.hpp:99
constexpr void Reset(Distance_t measuredPosition, Velocity_t measuredVelocity)
Reset the previous error and the integral term.
Definition ProfiledPIDController.hpp:403
constexpr ProfiledPIDController & operator=(ProfiledPIDController &&)=default
constexpr void SetTolerance(Distance_t positionTolerance, Velocity_t velocityTolerance=Velocity_t{ std::numeric_limits< double >::infinity()})
Sets the error which is considered tolerable for use with AtSetpoint().
Definition ProfiledPIDController.hpp:300
constexpr void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
Definition ProfiledPIDController.hpp:90
void InitSendable(wpi::util::SendableBuilder &builder) override
Initializes this Sendable object.
Definition ProfiledPIDController.hpp:418
constexpr double GetPositionTolerance() const
Gets the position tolerance of this controller.
Definition ProfiledPIDController.hpp:170
typename TrapezoidProfile< Distance >::State State
Definition ProfiledPIDController.hpp:43
wpi::units::compound_unit< Velocity, wpi::units::inverse< wpi::units::seconds > > Acceleration
Definition ProfiledPIDController.hpp:39
constexpr Distance_t GetPositionError() const
Returns the difference between the setpoint and the measurement.
Definition ProfiledPIDController.hpp:312
constexpr void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
Definition ProfiledPIDController.hpp:106
constexpr Velocity_t GetVelocityError() const
Returns the change in error per second.
Definition ProfiledPIDController.hpp:319
constexpr void DisableContinuousInput()
Disables continuous input.
Definition ProfiledPIDController.hpp:274
constexpr double Calculate(Distance_t measurement)
Returns the next output of the PID controller.
Definition ProfiledPIDController.hpp:328
constexpr ProfiledPIDController(const ProfiledPIDController &)=default
constexpr double GetP() const
Gets the proportional coefficient.
Definition ProfiledPIDController.hpp:133
constexpr double GetAccumulatedError() const
Gets the accumulated error used in the integral calculation of this controller.
Definition ProfiledPIDController.hpp:189
constexpr State GetSetpoint() const
Returns the current setpoint of the ProfiledPIDController.
Definition ProfiledPIDController.hpp:240
constexpr wpi::units::second_t GetPeriod() const
Gets the period of this controller.
Definition ProfiledPIDController.hpp:161
constexpr void Reset(Distance_t measuredPosition)
Reset the previous error and the integral term.
Definition ProfiledPIDController.hpp:414
constexpr void Reset(const State &measurement)
Reset the previous error and the integral term.
Definition ProfiledPIDController.hpp:392
wpi::units::compound_unit< Distance, wpi::units::inverse< wpi::units::seconds > > Velocity
Definition ProfiledPIDController.hpp:35
constexpr double Calculate(Distance_t measurement, Distance_t goal, typename wpi::math::TrapezoidProfile< Distance >::Constraints constraints)
Returns the next output of the PID controller.
Definition ProfiledPIDController.hpp:380
constexpr bool AtGoal() const
Returns true if the error is within the tolerance of the error.
Definition ProfiledPIDController.hpp:217
constexpr double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
Definition ProfiledPIDController.hpp:179
constexpr void SetGoal(Distance_t goal)
Sets the goal for the ProfiledPIDController.
Definition ProfiledPIDController.hpp:205
constexpr double Calculate(Distance_t measurement, State goal)
Returns the next output of the PID controller.
Definition ProfiledPIDController.hpp:358
constexpr ProfiledPIDController(double Kp, double Ki, double Kd, Constraints constraints, wpi::units::second_t period=20_ms)
Allocates a ProfiledPIDController with the given constants for Kp, Ki, and Kd.
Definition ProfiledPIDController.hpp:58
constexpr void EnableContinuousInput(Distance_t minimumInput, Distance_t maximumInput)
Enables continuous input.
Definition ProfiledPIDController.hpp:263
constexpr void SetGoal(State goal)
Sets the goal for the ProfiledPIDController.
Definition ProfiledPIDController.hpp:198
constexpr double Calculate(Distance_t measurement, Distance_t goal)
Returns the next output of the PID controller.
Definition ProfiledPIDController.hpp:368
wpi::units::unit_t< Distance > Distance_t
Definition ProfiledPIDController.hpp:34
constexpr void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum contributions of the integral term.
Definition ProfiledPIDController.hpp:288
wpi::units::unit_t< Velocity > Velocity_t
Definition ProfiledPIDController.hpp:38
constexpr ~ProfiledPIDController() override=default
constexpr void SetIZone(double iZone)
Sets the IZone range.
Definition ProfiledPIDController.hpp:126
typename TrapezoidProfile< Distance >::Constraints Constraints
Definition ProfiledPIDController.hpp:44
constexpr bool AtSetpoint() const
Returns true if the error is within the tolerance of the error.
Definition ProfiledPIDController.hpp:251
constexpr double GetIZone() const
Get the IZone range.
Definition ProfiledPIDController.hpp:154
constexpr ProfiledPIDController(ProfiledPIDController &&)=default
constexpr double GetI() const
Gets the integral coefficient.
Definition ProfiledPIDController.hpp:140
constexpr void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
Definition ProfiledPIDController.hpp:113
constexpr Constraints GetConstraints()
Get the velocity and acceleration constraints for this controller.
Definition ProfiledPIDController.hpp:233
wpi::units::unit_t< Acceleration > Acceleration_t
Definition ProfiledPIDController.hpp:42
constexpr double GetD() const
Gets the differential coefficient.
Definition ProfiledPIDController.hpp:147
constexpr ProfiledPIDController & operator=(const ProfiledPIDController &)=default
constexpr void SetConstraints(Constraints constraints)
Set velocity and acceleration constraints for goal.
Definition ProfiledPIDController.hpp:224
constexpr State GetGoal() const
Gets the goal for the ProfiledPIDController.
Definition ProfiledPIDController.hpp:210
Profile constraints.
Definition TrapezoidProfile.hpp:61
Profile state.
Definition TrapezoidProfile.hpp:100
A trapezoid-shaped velocity profile.
Definition TrapezoidProfile.hpp:46
Helper class for building Sendable dashboard representations.
Definition SendableBuilder.hpp:21
virtual void SetSmartDashboardType(std::string_view type)=0
Set the string representation of the named data type that will be used by the smart dashboard for thi...
virtual void AddDoubleProperty(std::string_view key, std::function< double()> getter, std::function< void(double)> setter)=0
Add a double property.
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.
Converts a string literal into a format string that will be parsed at compile time and converted into...
Definition printf.h:50
WPILIB_DLLEXPORT int IncrementAndGetProfiledPIDControllerInstances()
Definition LinearSystem.hpp:20
constexpr T InputModulus(T input, T minimumInput, T maximumInput)
Returns modulus of input.
Definition MathUtil.hpp:205