001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.math.controller;
006
007import edu.wpi.first.math.MathSharedStore;
008import edu.wpi.first.math.MathUsageId;
009import edu.wpi.first.math.MathUtil;
010import edu.wpi.first.util.sendable.Sendable;
011import edu.wpi.first.util.sendable.SendableBuilder;
012import edu.wpi.first.util.sendable.SendableRegistry;
013
014/** Implements a PID control loop. */
015public class PIDController implements Sendable, AutoCloseable {
016  private static int instances;
017
018  // Factor for "proportional" control
019  private double m_kp;
020
021  // Factor for "integral" control
022  private double m_ki;
023
024  // Factor for "derivative" control
025  private double m_kd;
026
027  // The period (in seconds) of the loop that calls the controller
028  private final double m_period;
029
030  private double m_maximumIntegral = 1.0;
031
032  private double m_minimumIntegral = -1.0;
033
034  private double m_maximumInput;
035
036  private double m_minimumInput;
037
038  // Do the endpoints wrap around? eg. Absolute encoder
039  private boolean m_continuous;
040
041  // The error at the time of the most recent call to calculate()
042  private double m_positionError;
043  private double m_velocityError;
044
045  // The error at the time of the second-most-recent call to calculate() (used to compute velocity)
046  private double m_prevError;
047
048  // The sum of the errors for use in the integral calc
049  private double m_totalError;
050
051  // The error that is considered at setpoint.
052  private double m_positionTolerance = 0.05;
053  private double m_velocityTolerance = Double.POSITIVE_INFINITY;
054
055  private double m_setpoint;
056  private double m_measurement;
057
058  /**
059   * Allocates a PIDController with the given constants for kp, ki, and kd and a default period of
060   * 0.02 seconds.
061   *
062   * @param kp The proportional coefficient.
063   * @param ki The integral coefficient.
064   * @param kd The derivative coefficient.
065   */
066  public PIDController(double kp, double ki, double kd) {
067    this(kp, ki, kd, 0.02);
068  }
069
070  /**
071   * Allocates a PIDController with the given constants for kp, ki, and kd.
072   *
073   * @param kp The proportional coefficient.
074   * @param ki The integral coefficient.
075   * @param kd The derivative coefficient.
076   * @param period The period between controller updates in seconds. Must be non-zero and positive.
077   */
078  public PIDController(double kp, double ki, double kd, double period) {
079    m_kp = kp;
080    m_ki = ki;
081    m_kd = kd;
082
083    if (period <= 0) {
084      throw new IllegalArgumentException("Controller period must be a non-zero positive number!");
085    }
086    m_period = period;
087
088    instances++;
089    SendableRegistry.addLW(this, "PIDController", instances);
090
091    MathSharedStore.reportUsage(MathUsageId.kController_PIDController2, instances);
092  }
093
094  @Override
095  public void close() {
096    SendableRegistry.remove(this);
097  }
098
099  /**
100   * Sets the PID Controller gain parameters.
101   *
102   * <p>Set the proportional, integral, and differential coefficients.
103   *
104   * @param kp The proportional coefficient.
105   * @param ki The integral coefficient.
106   * @param kd The derivative coefficient.
107   */
108  public void setPID(double kp, double ki, double kd) {
109    m_kp = kp;
110    m_ki = ki;
111    m_kd = kd;
112  }
113
114  /**
115   * Sets the Proportional coefficient of the PID controller gain.
116   *
117   * @param kp proportional coefficient
118   */
119  public void setP(double kp) {
120    m_kp = kp;
121  }
122
123  /**
124   * Sets the Integral coefficient of the PID controller gain.
125   *
126   * @param ki integral coefficient
127   */
128  public void setI(double ki) {
129    m_ki = ki;
130  }
131
132  /**
133   * Sets the Differential coefficient of the PID controller gain.
134   *
135   * @param kd differential coefficient
136   */
137  public void setD(double kd) {
138    m_kd = kd;
139  }
140
141  /**
142   * Get the Proportional coefficient.
143   *
144   * @return proportional coefficient
145   */
146  public double getP() {
147    return m_kp;
148  }
149
150  /**
151   * Get the Integral coefficient.
152   *
153   * @return integral coefficient
154   */
155  public double getI() {
156    return m_ki;
157  }
158
159  /**
160   * Get the Differential coefficient.
161   *
162   * @return differential coefficient
163   */
164  public double getD() {
165    return m_kd;
166  }
167
168  /**
169   * Returns the period of this controller.
170   *
171   * @return the period of the controller.
172   */
173  public double getPeriod() {
174    return m_period;
175  }
176
177  /**
178   * Sets the setpoint for the PIDController.
179   *
180   * @param setpoint The desired setpoint.
181   */
182  public void setSetpoint(double setpoint) {
183    m_setpoint = setpoint;
184  }
185
186  /**
187   * Returns the current setpoint of the PIDController.
188   *
189   * @return The current setpoint.
190   */
191  public double getSetpoint() {
192    return m_setpoint;
193  }
194
195  /**
196   * Returns true if the error is within the tolerance of the setpoint.
197   *
198   * <p>This will return false until at least one input value has been computed.
199   *
200   * @return Whether the error is within the acceptable bounds.
201   */
202  public boolean atSetpoint() {
203    double positionError;
204    if (m_continuous) {
205      double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
206      positionError = MathUtil.inputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
207    } else {
208      positionError = m_setpoint - m_measurement;
209    }
210
211    double velocityError = (positionError - m_prevError) / m_period;
212
213    return Math.abs(positionError) < m_positionTolerance
214        && Math.abs(velocityError) < m_velocityTolerance;
215  }
216
217  /**
218   * Enables continuous input.
219   *
220   * <p>Rather then using the max and min input range as constraints, it considers them to be the
221   * same point and automatically calculates the shortest route to the setpoint.
222   *
223   * @param minimumInput The minimum value expected from the input.
224   * @param maximumInput The maximum value expected from the input.
225   */
226  public void enableContinuousInput(double minimumInput, double maximumInput) {
227    m_continuous = true;
228    m_minimumInput = minimumInput;
229    m_maximumInput = maximumInput;
230  }
231
232  /** Disables continuous input. */
233  public void disableContinuousInput() {
234    m_continuous = false;
235  }
236
237  /**
238   * Returns true if continuous input is enabled.
239   *
240   * @return True if continuous input is enabled.
241   */
242  public boolean isContinuousInputEnabled() {
243    return m_continuous;
244  }
245
246  /**
247   * Sets the minimum and maximum values for the integrator.
248   *
249   * <p>When the cap is reached, the integrator value is added to the controller output rather than
250   * the integrator value times the integral gain.
251   *
252   * @param minimumIntegral The minimum value of the integrator.
253   * @param maximumIntegral The maximum value of the integrator.
254   */
255  public void setIntegratorRange(double minimumIntegral, double maximumIntegral) {
256    m_minimumIntegral = minimumIntegral;
257    m_maximumIntegral = maximumIntegral;
258  }
259
260  /**
261   * Sets the error which is considered tolerable for use with atSetpoint().
262   *
263   * @param positionTolerance Position error which is tolerable.
264   */
265  public void setTolerance(double positionTolerance) {
266    setTolerance(positionTolerance, Double.POSITIVE_INFINITY);
267  }
268
269  /**
270   * Sets the error which is considered tolerable for use with atSetpoint().
271   *
272   * @param positionTolerance Position error which is tolerable.
273   * @param velocityTolerance Velocity error which is tolerable.
274   */
275  public void setTolerance(double positionTolerance, double velocityTolerance) {
276    m_positionTolerance = positionTolerance;
277    m_velocityTolerance = velocityTolerance;
278  }
279
280  /**
281   * Returns the difference between the setpoint and the measurement.
282   *
283   * @return The error.
284   */
285  public double getPositionError() {
286    return m_positionError;
287  }
288
289  /**
290   * Returns the velocity error.
291   *
292   * @return The velocity error.
293   */
294  public double getVelocityError() {
295    return m_velocityError;
296  }
297
298  /**
299   * Returns the next output of the PID controller.
300   *
301   * @param measurement The current measurement of the process variable.
302   * @param setpoint The new setpoint of the controller.
303   * @return The next controller output.
304   */
305  public double calculate(double measurement, double setpoint) {
306    // Set setpoint to provided value
307    setSetpoint(setpoint);
308    return calculate(measurement);
309  }
310
311  /**
312   * Returns the next output of the PID controller.
313   *
314   * @param measurement The current measurement of the process variable.
315   * @return The next controller output.
316   */
317  public double calculate(double measurement) {
318    m_measurement = measurement;
319    m_prevError = m_positionError;
320
321    if (m_continuous) {
322      double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
323      m_positionError = MathUtil.inputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
324    } else {
325      m_positionError = m_setpoint - measurement;
326    }
327
328    m_velocityError = (m_positionError - m_prevError) / m_period;
329
330    if (m_ki != 0) {
331      m_totalError =
332          MathUtil.clamp(
333              m_totalError + m_positionError * m_period,
334              m_minimumIntegral / m_ki,
335              m_maximumIntegral / m_ki);
336    }
337
338    return m_kp * m_positionError + m_ki * m_totalError + m_kd * m_velocityError;
339  }
340
341  /** Resets the previous error and the integral term. */
342  public void reset() {
343    m_prevError = 0;
344    m_totalError = 0;
345  }
346
347  @Override
348  public void initSendable(SendableBuilder builder) {
349    builder.setSmartDashboardType("PIDController");
350    builder.addDoubleProperty("p", this::getP, this::setP);
351    builder.addDoubleProperty("i", this::getI, this::setI);
352    builder.addDoubleProperty("d", this::getD, this::setD);
353    builder.addDoubleProperty("setpoint", this::getSetpoint, this::setSetpoint);
354  }
355}