001/*
002 * Copyright (C) Cross The Road Electronics.  All rights reserved.
003 * License information can be found in CTRE_LICENSE.txt
004 * For support and suggestions contact support@ctr-electronics.com or file
005 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases
006 */
007package com.ctre.phoenix6.swerve.utility;
008
009import edu.wpi.first.math.MathSharedStore;
010import edu.wpi.first.math.MathUsageId;
011import edu.wpi.first.math.MathUtil;
012import edu.wpi.first.util.sendable.Sendable;
013import edu.wpi.first.util.sendable.SendableBuilder;
014import edu.wpi.first.util.sendable.SendableRegistry;
015
016/**
017 * Phoenix-centric PID controller taken from WPI's {@link edu.wpi.first.math.controller.PIDController} class.
018 * <p>
019 * This class differs from the WPI implementation by using explicit timestamps for
020 * integral/derivative calculations. Ideally, these timestamps come from the {@link com.ctre.phoenix6.StatusSignal}.
021 */
022public class PhoenixPIDController implements Sendable, AutoCloseable {
023  private static int instances;
024
025  // Factor for "proportional" control
026  private double m_kp;
027
028  // Factor for "integral" control
029  private double m_ki;
030
031  // Factor for "derivative" control
032  private double m_kd;
033
034  // The error range where "integral" control applies
035  private double m_iZone = Double.POSITIVE_INFINITY;
036
037  private double m_maximumIntegral = 1.0;
038
039  private double m_minimumIntegral = -1.0;
040
041  private double m_maximumInput;
042
043  private double m_minimumInput;
044
045  // Do the endpoints wrap around? e.g. Absolute encoder
046  private boolean m_continuous;
047
048  // The error at the time of the most recent call to calculate()
049  private double m_positionError;
050  private double m_velocityError;
051
052  // The error at the time of the second-most-recent call to calculate() (used to compute velocity)
053  private double m_prevError;
054
055  // The sum of the errors for use in the integral calc
056  private double m_totalError;
057
058  // The error that is considered at setpoint.
059  private double m_positionTolerance = 0.05;
060  private double m_velocityTolerance = Double.POSITIVE_INFINITY;
061
062  private double m_setpoint;
063  private double m_measurement;
064
065  private boolean m_haveMeasurement;
066  private boolean m_haveSetpoint;
067
068  private double m_lastAppliedOutput;
069
070  // The last timestamp acquired when performing a calculation
071  private double m_lastTimestamp;
072
073  /**
074   * Allocates a PIDController with the given constants for kp, ki, and kd.
075   *
076   * @param kp The proportional coefficient.
077   * @param ki The integral coefficient.
078   * @param kd The derivative coefficient.
079   */
080  @SuppressWarnings("this-escape")
081  public PhoenixPIDController(double kp, double ki, double kd) {
082    m_kp = kp;
083    m_ki = ki;
084    m_kd = kd;
085
086    instances++;
087    SendableRegistry.addLW(this, "PIDController", instances);
088
089    MathSharedStore.reportUsage(MathUsageId.kController_PIDController2, instances);
090  }
091
092  @Override
093  public void close() {
094    SendableRegistry.remove(this);
095  }
096
097  /**
098   * Sets the PID Controller gain parameters.
099   *
100   * <p>Set the proportional, integral, and differential coefficients.
101   *
102   * @param kp The proportional coefficient.
103   * @param ki The integral coefficient.
104   * @param kd The derivative coefficient.
105   */
106  public void setPID(double kp, double ki, double kd) {
107    m_kp = kp;
108    m_ki = ki;
109    m_kd = kd;
110  }
111
112  /**
113   * Sets the Proportional coefficient of the PID controller gain.
114   *
115   * @param kp proportional coefficient
116   */
117  public void setP(double kp) {
118    m_kp = kp;
119  }
120
121  /**
122   * Sets the Integral coefficient of the PID controller gain.
123   *
124   * @param ki integral coefficient
125   */
126  public void setI(double ki) {
127    m_ki = ki;
128  }
129
130  /**
131   * Sets the Differential coefficient of the PID controller gain.
132   *
133   * @param kd differential coefficient
134   */
135  public void setD(double kd) {
136    m_kd = kd;
137  }
138
139  /**
140   * Sets the IZone range. When the absolute value of the position error is greater than IZone, the
141   * total accumulated error will reset to zero, disabling integral gain until the absolute value of
142   * the position error is less than IZone. This is used to prevent integral windup. Must be
143   * non-negative. Passing a value of zero will effectively disable integral gain. Passing a value
144   * of {@link Double#POSITIVE_INFINITY} disables IZone functionality.
145   *
146   * @param iZone Maximum magnitude of error to allow integral control.
147   * @throws IllegalArgumentException if iZone &lt; 0
148   */
149  public void setIZone(double iZone) {
150    if (iZone < 0) {
151      throw new IllegalArgumentException("IZone must be a non-negative number!");
152    }
153    m_iZone = iZone;
154  }
155
156  /**
157   * Get the Proportional coefficient.
158   *
159   * @return proportional coefficient
160   */
161  public double getP() {
162    return m_kp;
163  }
164
165  /**
166   * Get the Integral coefficient.
167   *
168   * @return integral coefficient
169   */
170  public double getI() {
171    return m_ki;
172  }
173
174  /**
175   * Get the Differential coefficient.
176   *
177   * @return differential coefficient
178   */
179  public double getD() {
180    return m_kd;
181  }
182
183  /**
184   * Get the IZone range.
185   *
186   * @return Maximum magnitude of error to allow integral control.
187   */
188  public double getIZone() {
189    return m_iZone;
190  }
191
192  /**
193   * Returns the position tolerance of this controller.
194   *
195   * @return the position tolerance of the controller.
196   */
197  public double getPositionTolerance() {
198    return m_positionTolerance;
199  }
200
201  /**
202   * Returns the velocity tolerance of this controller.
203   *
204   * @return the velocity tolerance of the controller.
205   */
206  public double getVelocityTolerance() {
207    return m_velocityTolerance;
208  }
209
210  /**
211   * Returns the current setpoint of the PIDController.
212   *
213   * @return The current setpoint.
214   */
215  public double getSetpoint() {
216    return m_setpoint;
217  }
218
219  /**
220   * Returns true if the error is within the tolerance of the setpoint.
221   *
222   * <p>This will return false until at least one input value has been computed.
223   *
224   * @return Whether the error is within the acceptable bounds.
225   */
226  public boolean atSetpoint() {
227    return m_haveMeasurement
228        && m_haveSetpoint
229        && Math.abs(m_positionError) < m_positionTolerance
230        && Math.abs(m_velocityError) < m_velocityTolerance;
231  }
232
233  /**
234   * Enables continuous input.
235   *
236   * <p>Rather then using the max and min input range as constraints, it considers them to be the
237   * same point and automatically calculates the shortest route to the setpoint.
238   *
239   * @param minimumInput The minimum value expected from the input.
240   * @param maximumInput The maximum value expected from the input.
241   */
242  public void enableContinuousInput(double minimumInput, double maximumInput) {
243    m_continuous = true;
244    m_minimumInput = minimumInput;
245    m_maximumInput = maximumInput;
246  }
247
248  /** Disables continuous input. */
249  public void disableContinuousInput() {
250    m_continuous = false;
251  }
252
253  /**
254   * Returns true if continuous input is enabled.
255   *
256   * @return True if continuous input is enabled.
257   */
258  public boolean isContinuousInputEnabled() {
259    return m_continuous;
260  }
261
262  /**
263   * Sets the minimum and maximum values for the integrator.
264   *
265   * <p>When the cap is reached, the integrator value is added to the controller output rather than
266   * the integrator value times the integral gain.
267   *
268   * @param minimumIntegral The minimum value of the integrator.
269   * @param maximumIntegral The maximum value of the integrator.
270   */
271  public void setIntegratorRange(double minimumIntegral, double maximumIntegral) {
272    m_minimumIntegral = minimumIntegral;
273    m_maximumIntegral = maximumIntegral;
274  }
275
276  /**
277   * Sets the error which is considered tolerable for use with atSetpoint().
278   *
279   * @param positionTolerance Position error which is tolerable.
280   */
281  public void setTolerance(double positionTolerance) {
282    setTolerance(positionTolerance, Double.POSITIVE_INFINITY);
283  }
284
285  /**
286   * Sets the error which is considered tolerable for use with atSetpoint().
287   *
288   * @param positionTolerance Position error which is tolerable.
289   * @param velocityTolerance Velocity error which is tolerable.
290   */
291  public void setTolerance(double positionTolerance, double velocityTolerance) {
292    m_positionTolerance = positionTolerance;
293    m_velocityTolerance = velocityTolerance;
294  }
295
296  /**
297   * Returns the difference between the setpoint and the measurement.
298   *
299   * @return The error.
300   */
301  public double getPositionError() {
302    return m_positionError;
303  }
304
305  /**
306   * Returns the velocity error.
307   *
308   * @return The velocity error.
309   */
310  public double getVelocityError() {
311    return m_velocityError;
312  }
313
314  /**
315   * Returns the next output of the PID controller.
316   *
317   * @param measurement The current measurement of the process variable.
318   * @param setpoint The setpoint to target
319   * @param currentTimestamp The current timestamp to use for calculating integral/derivative error
320   * @return The next controller output.
321   */
322  public double calculate(double measurement, double setpoint, double currentTimestamp) {
323    m_setpoint = setpoint;
324    m_haveSetpoint = true;
325    m_measurement = measurement;
326    m_haveMeasurement = true;
327    m_prevError = m_positionError;
328
329    double thisPeriod = currentTimestamp - m_lastTimestamp;
330    m_lastTimestamp = currentTimestamp;
331
332    if (m_continuous) {
333      double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
334      m_positionError = MathUtil.inputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
335    } else {
336      m_positionError = m_setpoint - m_measurement;
337    }
338
339    m_velocityError = (m_positionError - m_prevError) / thisPeriod;
340
341    // If the absolute value of the position error is greater than IZone, reset the total error
342    if (Math.abs(m_positionError) > m_iZone) {
343      m_totalError = 0;
344    } else if (m_ki != 0) {
345      m_totalError =
346          MathUtil.clamp(
347              m_totalError + m_positionError * thisPeriod,
348              m_minimumIntegral / m_ki,
349              m_maximumIntegral / m_ki);
350    }
351
352    m_lastAppliedOutput = m_kp * m_positionError + m_ki * m_totalError + m_kd * m_velocityError;
353    return m_lastAppliedOutput;
354  }
355
356  /** Returns the last applied output from this PID controller. */
357  public double getLastAppliedOutput() {
358    return m_lastAppliedOutput;
359  }
360
361  /** Resets the previous error and the integral term. */
362  public void reset() {
363    m_positionError = 0;
364    m_prevError = 0;
365    m_totalError = 0;
366    m_velocityError = 0;
367    m_haveMeasurement = false;
368  }
369
370  @Override
371  public void initSendable(SendableBuilder builder) {
372    builder.setSmartDashboardType("PIDController");
373    builder.addDoubleProperty("p", this::getP, this::setP);
374    builder.addDoubleProperty("i", this::getI, this::setI);
375    builder.addDoubleProperty("d", this::getD, this::setD);
376    builder.addDoubleProperty("setpoint", this::getSetpoint, null);
377  }
378}