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