WPILibC++ 2023.4.3
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 * Gets the proportional coefficient.
111 *
112 * @return proportional coefficient
113 */
114 double GetP() const { return m_controller.GetP(); }
115
116 /**
117 * Gets the integral coefficient.
118 *
119 * @return integral coefficient
120 */
121 double GetI() const { return m_controller.GetI(); }
122
123 /**
124 * Gets the differential coefficient.
125 *
126 * @return differential coefficient
127 */
128 double GetD() const { return m_controller.GetD(); }
129
130 /**
131 * Gets the period of this controller.
132 *
133 * @return The period of the controller.
134 */
135 units::second_t GetPeriod() const { return m_controller.GetPeriod(); }
136
137 /**
138 * Gets the position tolerance of this controller.
139 *
140 * @return The position tolerance of the controller.
141 */
142 double GetPositionTolerance() const {
143 return m_controller.GetPositionTolerance();
144 }
145
146 /**
147 * Gets the velocity tolerance of this controller.
148 *
149 * @return The velocity tolerance of the controller.
150 */
151 double GetVelocityTolerance() const {
152 return m_controller.GetVelocityTolerance();
153 }
154
155 /**
156 * Sets the goal for the ProfiledPIDController.
157 *
158 * @param goal The desired unprofiled setpoint.
159 */
160 void SetGoal(State goal) { m_goal = goal; }
161
162 /**
163 * Sets the goal for the ProfiledPIDController.
164 *
165 * @param goal The desired unprofiled setpoint.
166 */
167 void SetGoal(Distance_t goal) { m_goal = {goal, Velocity_t{0}}; }
168
169 /**
170 * Gets the goal for the ProfiledPIDController.
171 */
172 State GetGoal() const { return m_goal; }
173
174 /**
175 * Returns true if the error is within the tolerance of the error.
176 *
177 * This will return false until at least one input value has been computed.
178 */
179 bool AtGoal() const { return AtSetpoint() && m_goal == m_setpoint; }
180
181 /**
182 * Set velocity and acceleration constraints for goal.
183 *
184 * @param constraints Velocity and acceleration constraints for goal.
185 */
186 void SetConstraints(Constraints constraints) { m_constraints = constraints; }
187
188 /**
189 * Returns the current setpoint of the ProfiledPIDController.
190 *
191 * @return The current setpoint.
192 */
193 State GetSetpoint() const { return m_setpoint; }
194
195 /**
196 * Returns true if the error is within the tolerance of the error.
197 *
198 * Currently this just reports on target as the actual value passes through
199 * the setpoint. Ideally it should be based on being within the tolerance for
200 * some period of time.
201 *
202 * This will return false until at least one input value has been computed.
203 */
204 bool AtSetpoint() const { return m_controller.AtSetpoint(); }
205
206 /**
207 * Enables continuous input.
208 *
209 * Rather then using the max and min input range as constraints, it considers
210 * them to be the same point and automatically calculates the shortest route
211 * to the setpoint.
212 *
213 * @param minimumInput The minimum value expected from the input.
214 * @param maximumInput The maximum value expected from the input.
215 */
216 void EnableContinuousInput(Distance_t minimumInput, Distance_t maximumInput) {
217 m_controller.EnableContinuousInput(minimumInput.value(),
218 maximumInput.value());
219 m_minimumInput = minimumInput;
220 m_maximumInput = maximumInput;
221 }
222
223 /**
224 * Disables continuous input.
225 */
227
228 /**
229 * Sets the minimum and maximum values for the integrator.
230 *
231 * When the cap is reached, the integrator value is added to the controller
232 * output rather than the integrator value times the integral gain.
233 *
234 * @param minimumIntegral The minimum value of the integrator.
235 * @param maximumIntegral The maximum value of the integrator.
236 */
237 void SetIntegratorRange(double minimumIntegral, double maximumIntegral) {
238 m_controller.SetIntegratorRange(minimumIntegral, maximumIntegral);
239 }
240
241 /**
242 * Sets the error which is considered tolerable for use with
243 * AtSetpoint().
244 *
245 * @param positionTolerance Position error which is tolerable.
246 * @param velocityTolerance Velocity error which is tolerable.
247 */
248 void SetTolerance(Distance_t positionTolerance,
249 Velocity_t velocityTolerance = Velocity_t{
250 std::numeric_limits<double>::infinity()}) {
251 m_controller.SetTolerance(positionTolerance.value(),
252 velocityTolerance.value());
253 }
254
255 /**
256 * Returns the difference between the setpoint and the measurement.
257 *
258 * @return The error.
259 */
261 return Distance_t{m_controller.GetPositionError()};
262 }
263
264 /**
265 * Returns the change in error per second.
266 */
268 return Velocity_t{m_controller.GetVelocityError()};
269 }
270
271 /**
272 * Returns the next output of the PID controller.
273 *
274 * @param measurement The current measurement of the process variable.
275 */
276 double Calculate(Distance_t measurement) {
277 if (m_controller.IsContinuousInputEnabled()) {
278 // Get error which is smallest distance between goal and measurement
279 auto errorBound = (m_maximumInput - m_minimumInput) / 2.0;
280 auto goalMinDistance = frc::InputModulus<Distance_t>(
281 m_goal.position - measurement, -errorBound, errorBound);
282 auto setpointMinDistance = frc::InputModulus<Distance_t>(
283 m_setpoint.position - measurement, -errorBound, errorBound);
284
285 // Recompute the profile goal with the smallest error, thus giving the
286 // shortest path. The goal may be outside the input range after this
287 // operation, but that's OK because the controller will still go there and
288 // report an error of zero. In other words, the setpoint only needs to be
289 // offset from the measurement by the input range modulus; they don't need
290 // to be equal.
291 m_goal.position = goalMinDistance + measurement;
292 m_setpoint.position = setpointMinDistance + measurement;
293 }
294
295 frc::TrapezoidProfile<Distance> profile{m_constraints, m_goal, m_setpoint};
296 m_setpoint = profile.Calculate(GetPeriod());
297 return m_controller.Calculate(measurement.value(),
298 m_setpoint.position.value());
299 }
300
301 /**
302 * Returns the next output of the PID controller.
303 *
304 * @param measurement The current measurement of the process variable.
305 * @param goal The new goal of the controller.
306 */
307 double Calculate(Distance_t measurement, State goal) {
308 SetGoal(goal);
309 return Calculate(measurement);
310 }
311 /**
312 * Returns the next output of the PID controller.
313 *
314 * @param measurement The current measurement of the process variable.
315 * @param goal The new goal of the controller.
316 */
317 double Calculate(Distance_t measurement, Distance_t goal) {
318 SetGoal(goal);
319 return Calculate(measurement);
320 }
321
322 /**
323 * Returns the next output of the PID controller.
324 *
325 * @param measurement The current measurement of the process variable.
326 * @param goal The new goal of the controller.
327 * @param constraints Velocity and acceleration constraints for goal.
328 */
329 double Calculate(
330 Distance_t measurement, Distance_t goal,
332 SetConstraints(constraints);
333 return Calculate(measurement, goal);
334 }
335
336 /**
337 * Reset the previous error and the integral term.
338 *
339 * @param measurement The current measured State of the system.
340 */
341 void Reset(const State& measurement) {
342 m_controller.Reset();
343 m_setpoint = measurement;
344 }
345
346 /**
347 * Reset the previous error and the integral term.
348 *
349 * @param measuredPosition The current measured position of the system.
350 * @param measuredVelocity The current measured velocity of the system.
351 */
352 void Reset(Distance_t measuredPosition, Velocity_t measuredVelocity) {
353 Reset(State{measuredPosition, measuredVelocity});
354 }
355
356 /**
357 * Reset the previous error and the integral term.
358 *
359 * @param measuredPosition The current measured position of the system. The
360 * velocity is assumed to be zero.
361 */
362 void Reset(Distance_t measuredPosition) {
363 Reset(measuredPosition, Velocity_t{0});
364 }
365
366 void InitSendable(wpi::SendableBuilder& builder) override {
367 builder.SetSmartDashboardType("ProfiledPIDController");
368 builder.AddDoubleProperty(
369 "p", [this] { return GetP(); }, [this](double value) { SetP(value); });
370 builder.AddDoubleProperty(
371 "i", [this] { return GetI(); }, [this](double value) { SetI(value); });
372 builder.AddDoubleProperty(
373 "d", [this] { return GetD(); }, [this](double value) { SetD(value); });
374 builder.AddDoubleProperty(
375 "goal", [this] { return GetGoal().position.value(); },
376 [this](double value) { SetGoal(Distance_t{value}); });
377 }
378
379 private:
380 frc2::PIDController m_controller;
381 Distance_t m_minimumInput{0};
382 Distance_t m_maximumInput{0};
384 typename frc::TrapezoidProfile<Distance>::State m_setpoint;
386};
387
388} // 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.
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 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:114
State GetSetpoint() const
Returns the current setpoint of the ProfiledPIDController.
Definition: ProfiledPIDController.h:193
double Calculate(Distance_t measurement, Distance_t goal)
Returns the next output of the PID controller.
Definition: ProfiledPIDController.h:317
ProfiledPIDController & operator=(ProfiledPIDController &&)=default
void Reset(Distance_t measuredPosition)
Reset the previous error and the integral term.
Definition: ProfiledPIDController.h:362
State GetGoal() const
Gets the goal for the ProfiledPIDController.
Definition: ProfiledPIDController.h:172
bool AtSetpoint() const
Returns true if the error is within the tolerance of the error.
Definition: ProfiledPIDController.h:204
double Calculate(Distance_t measurement, State goal)
Returns the next output of the PID controller.
Definition: ProfiledPIDController.h:307
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:260
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:248
void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum values for the integrator.
Definition: ProfiledPIDController.h:237
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:167
void DisableContinuousInput()
Disables continuous input.
Definition: ProfiledPIDController.h:226
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:135
Velocity_t GetVelocityError() const
Returns the change in error per second.
Definition: ProfiledPIDController.h:267
double GetD() const
Gets the differential coefficient.
Definition: ProfiledPIDController.h:128
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:142
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:329
void EnableContinuousInput(Distance_t minimumInput, Distance_t maximumInput)
Enables continuous input.
Definition: ProfiledPIDController.h:216
ProfiledPIDController(ProfiledPIDController &&)=default
double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
Definition: ProfiledPIDController.h:151
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
Definition: ProfiledPIDController.h:366
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:341
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:276
void Reset(Distance_t measuredPosition, Velocity_t measuredVelocity)
Reset the previous error and the integral term.
Definition: ProfiledPIDController.h:352
void SetGoal(State goal)
Sets the goal for the ProfiledPIDController.
Definition: ProfiledPIDController.h:160
double GetI() const
Gets the integral coefficient.
Definition: ProfiledPIDController.h:121
~ProfiledPIDController() override=default
void SetConstraints(Constraints constraints)
Set velocity and acceleration constraints for goal.
Definition: ProfiledPIDController.h:186
bool AtGoal() const
Returns true if the error is within the tolerance of the error.
Definition: ProfiledPIDController.h:179
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:2107
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:1434
Definition: chrono.h:303
WPILIB_DLLEXPORT int IncrementAndGetProfiledPIDControllerInstances()
Definition: AprilTagFieldLayout.h:22