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