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