WPILibC++ 2023.4.3
PIDController.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 <functional>
8#include <limits>
9
10#include <wpi/SymbolExports.h>
13
14#include "units/time.h"
15
16namespace frc2 {
17
18/**
19 * Implements a PID control loop.
20 */
22 : public wpi::Sendable,
23 public wpi::SendableHelper<PIDController> {
24 public:
25 /**
26 * Allocates a PIDController with the given constants for Kp, Ki, and Kd.
27 *
28 * @param Kp The proportional coefficient.
29 * @param Ki The integral coefficient.
30 * @param Kd The derivative coefficient.
31 * @param period The period between controller updates in seconds. The
32 * default is 20 milliseconds. Must be non-zero and positive.
33 */
34 PIDController(double Kp, double Ki, double Kd,
35 units::second_t period = 20_ms);
36
37 ~PIDController() override = default;
38
39 PIDController(const PIDController&) = default;
43
44 /**
45 * Sets the PID Controller gain parameters.
46 *
47 * Sets the proportional, integral, and differential coefficients.
48 *
49 * @param Kp Proportional coefficient
50 * @param Ki Integral coefficient
51 * @param Kd Differential coefficient
52 */
53 void SetPID(double Kp, double Ki, double Kd);
54
55 /**
56 * Sets the proportional coefficient of the PID controller gain.
57 *
58 * @param Kp proportional coefficient
59 */
60 void SetP(double Kp);
61
62 /**
63 * Sets the integral coefficient of the PID controller gain.
64 *
65 * @param Ki integral coefficient
66 */
67 void SetI(double Ki);
68
69 /**
70 * Sets the differential coefficient of the PID controller gain.
71 *
72 * @param Kd differential coefficient
73 */
74 void SetD(double Kd);
75
76 /**
77 * Gets the proportional coefficient.
78 *
79 * @return proportional coefficient
80 */
81 double GetP() const;
82
83 /**
84 * Gets the integral coefficient.
85 *
86 * @return integral coefficient
87 */
88 double GetI() const;
89
90 /**
91 * Gets the differential coefficient.
92 *
93 * @return differential coefficient
94 */
95 double GetD() const;
96
97 /**
98 * Gets the period of this controller.
99 *
100 * @return The period of the controller.
101 */
102 units::second_t GetPeriod() const;
103
104 /**
105 * Gets the position tolerance of this controller.
106 *
107 * @return The position tolerance of the controller.
108 */
109 double GetPositionTolerance() const;
110
111 /**
112 * Gets the velocity tolerance of this controller.
113 *
114 * @return The velocity tolerance of the controller.
115 */
116 double GetVelocityTolerance() const;
117
118 /**
119 * Sets the setpoint for the PIDController.
120 *
121 * @param setpoint The desired setpoint.
122 */
123 void SetSetpoint(double setpoint);
124
125 /**
126 * Returns the current setpoint of the PIDController.
127 *
128 * @return The current setpoint.
129 */
130 double GetSetpoint() const;
131
132 /**
133 * Returns true if the error is within the tolerance of the setpoint.
134 *
135 * This will return false until at least one input value has been computed.
136 */
137 bool AtSetpoint() const;
138
139 /**
140 * Enables continuous input.
141 *
142 * Rather then using the max and min input range as constraints, it considers
143 * them to be the same point and automatically calculates the shortest route
144 * to the setpoint.
145 *
146 * @param minimumInput The minimum value expected from the input.
147 * @param maximumInput The maximum value expected from the input.
148 */
149 void EnableContinuousInput(double minimumInput, double maximumInput);
150
151 /**
152 * Disables continuous input.
153 */
155
156 /**
157 * Returns true if continuous input is enabled.
158 */
160
161 /**
162 * Sets the minimum and maximum values for the integrator.
163 *
164 * When the cap is reached, the integrator value is added to the controller
165 * output rather than the integrator value times the integral gain.
166 *
167 * @param minimumIntegral The minimum value of the integrator.
168 * @param maximumIntegral The maximum value of the integrator.
169 */
170 void SetIntegratorRange(double minimumIntegral, double maximumIntegral);
171
172 /**
173 * Sets the error which is considered tolerable for use with AtSetpoint().
174 *
175 * @param positionTolerance Position error which is tolerable.
176 * @param velocityTolerance Velocity error which is tolerable.
177 */
179 double positionTolerance,
180 double velocityTolerance = std::numeric_limits<double>::infinity());
181
182 /**
183 * Returns the difference between the setpoint and the measurement.
184 */
185 double GetPositionError() const;
186
187 /**
188 * Returns the velocity error.
189 */
190 double GetVelocityError() const;
191
192 /**
193 * Returns the next output of the PID controller.
194 *
195 * @param measurement The current measurement of the process variable.
196 */
197 double Calculate(double measurement);
198
199 /**
200 * Returns the next output of the PID controller.
201 *
202 * @param measurement The current measurement of the process variable.
203 * @param setpoint The new setpoint of the controller.
204 */
205 double Calculate(double measurement, double setpoint);
206
207 /**
208 * Reset the previous error, the integral term, and disable the controller.
209 */
210 void Reset();
211
212 void InitSendable(wpi::SendableBuilder& builder) override;
213
214 private:
215 // Factor for "proportional" control
216 double m_Kp;
217
218 // Factor for "integral" control
219 double m_Ki;
220
221 // Factor for "derivative" control
222 double m_Kd;
223
224 // The period (in seconds) of the control loop running this controller
225 units::second_t m_period;
226
227 double m_maximumIntegral = 1.0;
228
229 double m_minimumIntegral = -1.0;
230
231 double m_maximumInput = 0;
232
233 double m_minimumInput = 0;
234
235 // Do the endpoints wrap around? eg. Absolute encoder
236 bool m_continuous = false;
237
238 // The error at the time of the most recent call to Calculate()
239 double m_positionError = 0;
240 double m_velocityError = 0;
241
242 // The error at the time of the second-most-recent call to Calculate() (used
243 // to compute velocity)
244 double m_prevError = 0;
245
246 // The sum of the errors for use in the integral calc
247 double m_totalError = 0;
248
249 // The error that is considered at setpoint.
250 double m_positionTolerance = 0.05;
251 double m_velocityTolerance = std::numeric_limits<double>::infinity();
252
253 double m_setpoint = 0;
254 double m_measurement = 0;
255
256 bool m_haveSetpoint = false;
257 bool m_haveMeasurement = false;
258};
259
260} // namespace frc2
261
262namespace frc {
263
265
266} // 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 InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
void SetTolerance(double positionTolerance, double velocityTolerance=std::numeric_limits< double >::infinity())
Sets the error which is considered tolerable for use with AtSetpoint().
PIDController(double Kp, double Ki, double Kd, units::second_t period=20_ms)
Allocates a PIDController with the given constants for Kp, Ki, and Kd.
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.
double GetSetpoint() const
Returns the current setpoint of the PIDController.
PIDController(const PIDController &)=default
void SetSetpoint(double setpoint)
Sets the setpoint for the PIDController.
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.
PIDController & operator=(const PIDController &)=default
double Calculate(double measurement, double setpoint)
Returns the next output of the PID controller.
~PIDController() override=default
void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum values for the integrator.
PIDController(PIDController &&)=default
PIDController & operator=(PIDController &&)=default
bool IsContinuousInputEnabled() const
Returns true if continuous input is enabled.
Definition: SendableBuilder.h:18
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
Definition: InstantCommand.h:14
Definition: AprilTagFieldLayout.h:22