CTRE Phoenix 6 C++ 26.0.0-beta-1
Loading...
Searching...
No Matches
PhoenixPIDController.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) Cross The Road Electronics.  All rights reserved.
3 * License information can be found in CTRE_LICENSE.txt
4 * For support and suggestions contact support@ctr-electronics.com or file
5 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases
6 */
7#pragma once
8
9#include <limits>
10#include <units/time.h>
11
12namespace ctre {
13namespace phoenix6 {
14namespace swerve {
15
16/**
17 * \brief Phoenix-centric PID controller taken from WPI's frc#PIDController class.
18 *
19 * This class differs from the WPI implementation by using explicit timestamps for
20 * integral/derivative calculations. Ideally, these timestamps come from the StatusSignal.
21 */
23public:
24 /**
25 * Allocates a PhoenixPIDController with the given constants for Kp, Ki, and Kd.
26 *
27 * \param Kp The proportional coefficient. Must be >= 0.
28 * \param Ki The integral coefficient. Must be >= 0.
29 * \param Kd The derivative coefficient. Must be >= 0.
30 */
31 PhoenixPIDController(double Kp, double Ki, double Kd);
32
33 /**
34 * Sets the PID Controller gain parameters.
35 *
36 * Sets the proportional, integral, and differential coefficients.
37 *
38 * \param Kp The proportional coefficient. Must be >= 0.
39 * \param Ki The integral coefficient. Must be >= 0.
40 * \param Kd The differential coefficient. Must be >= 0.
41 */
42 void SetPID(double Kp, double Ki, double Kd);
43
44 /**
45 * Sets the proportional coefficient of the PID controller gain.
46 *
47 * \param Kp The proportional coefficient. Must be >= 0.
48 */
49 void SetP(double Kp);
50
51 /**
52 * Sets the integral coefficient of the PID controller gain.
53 *
54 * \param Ki The integral coefficient. Must be >= 0.
55 */
56 void SetI(double Ki);
57
58 /**
59 * Sets the differential coefficient of the PID controller gain.
60 *
61 * \param Kd The differential coefficient. Must be >= 0.
62 */
63 void SetD(double Kd);
64
65 /**
66 * Sets the IZone range. When the absolute value of the position error is
67 * greater than IZone, the total accumulated error will reset to zero,
68 * disabling integral gain until the absolute value of the position error is
69 * less than IZone. This is used to prevent integral windup. Must be
70 * non-negative. Passing a value of zero will effectively disable integral
71 * gain. Passing a value of infinity disables IZone functionality.
72 *
73 * \param iZone Maximum magnitude of error to allow integral control. Must be
74 * >= 0.
75 */
76 void SetIZone(double iZone);
77
78 /**
79 * Gets the proportional coefficient.
80 *
81 * \returns proportional coefficient
82 */
83 double GetP() const;
84
85 /**
86 * Gets the integral coefficient.
87 *
88 * \returns integral coefficient
89 */
90 double GetI() const;
91
92 /**
93 * Gets the differential coefficient.
94 *
95 * \returns differential coefficient
96 */
97 double GetD() const;
98
99 /**
100 * Get the IZone range.
101 *
102 * \returns Maximum magnitude of error to allow integral control.
103 */
104 double GetIZone() const;
105
106 /**
107 * Gets the position tolerance of this controller.
108 *
109 * \returns The position tolerance of the controller.
110 */
111 double GetPositionTolerance() const;
112
113 /**
114 * Gets the velocity tolerance of this controller.
115 *
116 * \returns The velocity tolerance of the controller.
117 */
118 double GetVelocityTolerance() const;
119
120 /**
121 * Returns the current setpoint of the PIDController.
122 *
123 * \returns The current setpoint.
124 */
125 double GetSetpoint() const;
126
127 /**
128 * Returns true if the error is within the tolerance of the setpoint.
129 *
130 * This will return false until at least one input value has been computed.
131 */
132 bool AtSetpoint() const;
133
134 /**
135 * Enables continuous input.
136 *
137 * Rather then using the max and min input range as constraints, it considers
138 * them to be the same point and automatically calculates the shortest route
139 * to the setpoint.
140 *
141 * \param minimumInput The minimum value expected from the input.
142 * \param maximumInput The maximum value expected from the input.
143 */
144 void EnableContinuousInput(double minimumInput, double maximumInput);
145
146 /**
147 * Disables continuous input.
148 */
150
151 /**
152 * Returns true if continuous input is enabled.
153 */
155
156 /**
157 * Sets the minimum and maximum values for the integrator.
158 *
159 * When the cap is reached, the integrator value is added to the controller
160 * output rather than the integrator value times the integral gain.
161 *
162 * \param minimumIntegral The minimum value of the integrator.
163 * \param maximumIntegral The maximum value of the integrator.
164 */
165 void SetIntegratorRange(double minimumIntegral, double maximumIntegral);
166
167 /**
168 * Sets the error which is considered tolerable for use with AtSetpoint().
169 *
170 * \param positionTolerance Position error which is tolerable.
171 * \param velocityTolerance Velocity error which is tolerable.
172 */
174 double positionTolerance,
175 double velocityTolerance = std::numeric_limits<double>::infinity());
176
177 /**
178 * Returns the difference between the setpoint and the measurement.
179 */
180 double GetPositionError() const;
181
182 /**
183 * Returns the velocity error.
184 */
185 double GetVelocityError() const;
186
187 /**
188 * Returns the next output of the PID controller.
189 *
190 * \param measurement The current measurement of the process variable.
191 * \param setpoint The new setpoint of the controller.
192 * \param currentTimestamp The current timestamp to use for calculating integral/derivative error
193 */
194 double Calculate(double measurement, double setpoint, units::second_t currentTimestamp);
195
196 /**
197 * Returns the last applied output from this PID controller.
198 */
199 double GetLastAppliedOutput() const;
200
201 /**
202 * Reset the previous error, the integral term, and disable the controller.
203 */
204 void Reset();
205
206private:
207 // Factor for "proportional" control
208 double m_Kp;
209
210 // Factor for "integral" control
211 double m_Ki;
212
213 // Factor for "derivative" control
214 double m_Kd;
215
216 // The error range where "integral" control applies
217 double m_iZone = std::numeric_limits<double>::infinity();
218
219 double m_maximumIntegral = 1.0;
220
221 double m_minimumIntegral = -1.0;
222
223 double m_maximumInput = 0;
224
225 double m_minimumInput = 0;
226
227 // Do the endpoints wrap around? eg. Absolute encoder
228 bool m_continuous = false;
229
230 // The error at the time of the most recent call to Calculate()
231 double m_positionError = 0;
232 double m_velocityError = 0;
233
234 // The error at the time of the second-most-recent call to Calculate() (used
235 // to compute velocity)
236 double m_prevError = 0;
237
238 // The sum of the errors for use in the integral calc
239 double m_totalError = 0;
240
241 // The error that is considered at setpoint.
242 double m_positionTolerance = 0.05;
243 double m_velocityTolerance = std::numeric_limits<double>::infinity();
244
245 double m_setpoint = 0;
246 double m_measurement = 0;
247
248 bool m_haveSetpoint = false;
249 bool m_haveMeasurement = false;
250
251 double m_lastAppliedOutput;
252
253 // The last timestamp acquired when performing a calculation
254 units::second_t m_lastTimestamp;
255};
256
257}
258}
259}
Phoenix-centric PID controller taken from WPI's frc#PIDController class.
Definition PhoenixPIDController.hpp:22
void DisableContinuousInput()
Disables continuous input.
void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
bool IsContinuousInputEnabled() const
Returns true if continuous input is enabled.
double GetLastAppliedOutput() const
Returns the last applied output from this PID controller.
double GetPositionError() const
Returns the difference between the setpoint and the measurement.
PhoenixPIDController(double Kp, double Ki, double Kd)
Allocates a PhoenixPIDController with the given constants for Kp, Ki, and Kd.
void SetP(double Kp)
Sets the proportional coefficient of the PID controller gain.
void Reset()
Reset the previous error, the integral term, and disable the controller.
void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum values for the integrator.
double GetVelocityError() const
Returns the velocity error.
double GetSetpoint() const
Returns the current setpoint of the PIDController.
bool AtSetpoint() const
Returns true if the error is within the tolerance of the setpoint.
double GetP() const
Gets the proportional coefficient.
void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
double GetI() const
Gets the integral coefficient.
double Calculate(double measurement, double setpoint, units::second_t currentTimestamp)
Returns the next output of the PID controller.
double GetPositionTolerance() const
Gets the position tolerance of this controller.
void EnableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.
void SetTolerance(double positionTolerance, double velocityTolerance=std::numeric_limits< double >::infinity())
Sets the error which is considered tolerable for use with AtSetpoint().
double GetIZone() const
Get the IZone range.
double GetD() const
Gets the differential coefficient.
void SetIZone(double iZone)
Sets the IZone range.
void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
Definition motor_constants.h:14