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.math.trajectory.TrapezoidProfile;
011import edu.wpi.first.util.sendable.Sendable;
012import edu.wpi.first.util.sendable.SendableBuilder;
013
014/**
015 * Implements a PID control loop whose setpoint is constrained by a trapezoid profile. Users should
016 * call reset() when they first start running the controller to avoid unwanted behavior.
017 */
018public class ProfiledPIDController implements Sendable {
019  private static int instances;
020
021  private PIDController m_controller;
022  private double m_minimumInput;
023  private double m_maximumInput;
024  private TrapezoidProfile.State m_goal = new TrapezoidProfile.State();
025  private TrapezoidProfile.State m_setpoint = new TrapezoidProfile.State();
026  private TrapezoidProfile.Constraints m_constraints;
027
028  /**
029   * Allocates a ProfiledPIDController with the given constants for Kp, Ki, and Kd.
030   *
031   * @param Kp The proportional coefficient.
032   * @param Ki The integral coefficient.
033   * @param Kd The derivative coefficient.
034   * @param constraints Velocity and acceleration constraints for goal.
035   */
036  @SuppressWarnings("ParameterName")
037  public ProfiledPIDController(
038      double Kp, double Ki, double Kd, TrapezoidProfile.Constraints constraints) {
039    this(Kp, Ki, Kd, constraints, 0.02);
040  }
041
042  /**
043   * Allocates a ProfiledPIDController with the given constants for Kp, Ki, and Kd.
044   *
045   * @param Kp The proportional coefficient.
046   * @param Ki The integral coefficient.
047   * @param Kd The derivative coefficient.
048   * @param constraints Velocity and acceleration constraints for goal.
049   * @param period The period between controller updates in seconds. The default is 0.02 seconds.
050   */
051  @SuppressWarnings("ParameterName")
052  public ProfiledPIDController(
053      double Kp, double Ki, double Kd, TrapezoidProfile.Constraints constraints, double period) {
054    m_controller = new PIDController(Kp, Ki, Kd, period);
055    m_constraints = constraints;
056    instances++;
057    MathSharedStore.reportUsage(MathUsageId.kController_ProfiledPIDController, instances);
058  }
059
060  /**
061   * Sets the PID Controller gain parameters.
062   *
063   * <p>Sets the proportional, integral, and differential coefficients.
064   *
065   * @param Kp Proportional coefficient
066   * @param Ki Integral coefficient
067   * @param Kd Differential coefficient
068   */
069  @SuppressWarnings("ParameterName")
070  public void setPID(double Kp, double Ki, double Kd) {
071    m_controller.setPID(Kp, Ki, Kd);
072  }
073
074  /**
075   * Sets the proportional coefficient of the PID controller gain.
076   *
077   * @param Kp proportional coefficient
078   */
079  @SuppressWarnings("ParameterName")
080  public void setP(double Kp) {
081    m_controller.setP(Kp);
082  }
083
084  /**
085   * Sets the integral coefficient of the PID controller gain.
086   *
087   * @param Ki integral coefficient
088   */
089  @SuppressWarnings("ParameterName")
090  public void setI(double Ki) {
091    m_controller.setI(Ki);
092  }
093
094  /**
095   * Sets the differential coefficient of the PID controller gain.
096   *
097   * @param Kd differential coefficient
098   */
099  @SuppressWarnings("ParameterName")
100  public void setD(double Kd) {
101    m_controller.setD(Kd);
102  }
103
104  /**
105   * Gets the proportional coefficient.
106   *
107   * @return proportional coefficient
108   */
109  public double getP() {
110    return m_controller.getP();
111  }
112
113  /**
114   * Gets the integral coefficient.
115   *
116   * @return integral coefficient
117   */
118  public double getI() {
119    return m_controller.getI();
120  }
121
122  /**
123   * Gets the differential coefficient.
124   *
125   * @return differential coefficient
126   */
127  public double getD() {
128    return m_controller.getD();
129  }
130
131  /**
132   * Gets the period of this controller.
133   *
134   * @return The period of the controller.
135   */
136  public double getPeriod() {
137    return m_controller.getPeriod();
138  }
139
140  /**
141   * Sets the goal for the ProfiledPIDController.
142   *
143   * @param goal The desired goal state.
144   */
145  public void setGoal(TrapezoidProfile.State goal) {
146    m_goal = goal;
147  }
148
149  /**
150   * Sets the goal for the ProfiledPIDController.
151   *
152   * @param goal The desired goal position.
153   */
154  public void setGoal(double goal) {
155    m_goal = new TrapezoidProfile.State(goal, 0);
156  }
157
158  /**
159   * Gets the goal for the ProfiledPIDController.
160   *
161   * @return The goal.
162   */
163  public TrapezoidProfile.State getGoal() {
164    return m_goal;
165  }
166
167  /**
168   * Returns true if the error is within the tolerance of the error.
169   *
170   * <p>This will return false until at least one input value has been computed.
171   *
172   * @return True if the error is within the tolerance of the error.
173   */
174  public boolean atGoal() {
175    return atSetpoint() && m_goal.equals(m_setpoint);
176  }
177
178  /**
179   * Set velocity and acceleration constraints for goal.
180   *
181   * @param constraints Velocity and acceleration constraints for goal.
182   */
183  public void setConstraints(TrapezoidProfile.Constraints constraints) {
184    m_constraints = constraints;
185  }
186
187  /**
188   * Returns the current setpoint of the ProfiledPIDController.
189   *
190   * @return The current setpoint.
191   */
192  public TrapezoidProfile.State getSetpoint() {
193    return m_setpoint;
194  }
195
196  /**
197   * Returns true if the error is within the tolerance of the error.
198   *
199   * <p>This will return false until at least one input value has been computed.
200   *
201   * @return True if the error is within the tolerance of the error.
202   */
203  public boolean atSetpoint() {
204    return m_controller.atSetpoint();
205  }
206
207  /**
208   * Enables continuous input.
209   *
210   * <p>Rather then using the max and min input range as constraints, it considers them to be the
211   * same point and automatically calculates the shortest route 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  public void enableContinuousInput(double minimumInput, double maximumInput) {
217    m_controller.enableContinuousInput(minimumInput, maximumInput);
218    m_minimumInput = minimumInput;
219    m_maximumInput = maximumInput;
220  }
221
222  /** Disables continuous input. */
223  public void disableContinuousInput() {
224    m_controller.disableContinuousInput();
225  }
226
227  /**
228   * Sets the minimum and maximum values for the integrator.
229   *
230   * <p>When the cap is reached, the integrator value is added to the controller output rather than
231   * the integrator value times the integral gain.
232   *
233   * @param minimumIntegral The minimum value of the integrator.
234   * @param maximumIntegral The maximum value of the integrator.
235   */
236  public void setIntegratorRange(double minimumIntegral, double maximumIntegral) {
237    m_controller.setIntegratorRange(minimumIntegral, maximumIntegral);
238  }
239
240  /**
241   * Sets the error which is considered tolerable for use with atSetpoint().
242   *
243   * @param positionTolerance Position error which is tolerable.
244   */
245  public void setTolerance(double positionTolerance) {
246    setTolerance(positionTolerance, Double.POSITIVE_INFINITY);
247  }
248
249  /**
250   * Sets the error which is considered tolerable for use with atSetpoint().
251   *
252   * @param positionTolerance Position error which is tolerable.
253   * @param velocityTolerance Velocity error which is tolerable.
254   */
255  public void setTolerance(double positionTolerance, double velocityTolerance) {
256    m_controller.setTolerance(positionTolerance, velocityTolerance);
257  }
258
259  /**
260   * Returns the difference between the setpoint and the measurement.
261   *
262   * @return The error.
263   */
264  public double getPositionError() {
265    return m_controller.getPositionError();
266  }
267
268  /**
269   * Returns the change in error per second.
270   *
271   * @return The change in error per second.
272   */
273  public double getVelocityError() {
274    return m_controller.getVelocityError();
275  }
276
277  /**
278   * Returns the next output of the PID controller.
279   *
280   * @param measurement The current measurement of the process variable.
281   * @return The controller's next output.
282   */
283  public double calculate(double measurement) {
284    if (m_controller.isContinuousInputEnabled()) {
285      // Get error which is smallest distance between goal and measurement
286      double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
287      double goalMinDistance =
288          MathUtil.inputModulus(m_goal.position - measurement, -errorBound, errorBound);
289      double setpointMinDistance =
290          MathUtil.inputModulus(m_setpoint.position - measurement, -errorBound, errorBound);
291
292      // Recompute the profile goal with the smallest error, thus giving the shortest path. The goal
293      // may be outside the input range after this operation, but that's OK because the controller
294      // will still go there and report an error of zero. In other words, the setpoint only needs to
295      // be offset from the measurement by the input range modulus; they don't need to be equal.
296      m_goal.position = goalMinDistance + measurement;
297      m_setpoint.position = setpointMinDistance + measurement;
298    }
299
300    var profile = new TrapezoidProfile(m_constraints, m_goal, m_setpoint);
301    m_setpoint = profile.calculate(getPeriod());
302    return m_controller.calculate(measurement, m_setpoint.position);
303  }
304
305  /**
306   * Returns the next output of the PID controller.
307   *
308   * @param measurement The current measurement of the process variable.
309   * @param goal The new goal of the controller.
310   * @return The controller's next output.
311   */
312  public double calculate(double measurement, TrapezoidProfile.State goal) {
313    setGoal(goal);
314    return calculate(measurement);
315  }
316
317  /**
318   * Returns the next output of the PIDController.
319   *
320   * @param measurement The current measurement of the process variable.
321   * @param goal The new goal of the controller.
322   * @return The controller's next output.
323   */
324  public double calculate(double measurement, double goal) {
325    setGoal(goal);
326    return calculate(measurement);
327  }
328
329  /**
330   * Returns the next output of the PID controller.
331   *
332   * @param measurement The current measurement of the process variable.
333   * @param goal The new goal of the controller.
334   * @param constraints Velocity and acceleration constraints for goal.
335   * @return The controller's next output.
336   */
337  public double calculate(
338      double measurement, TrapezoidProfile.State goal, TrapezoidProfile.Constraints constraints) {
339    setConstraints(constraints);
340    return calculate(measurement, goal);
341  }
342
343  /**
344   * Reset the previous error and the integral term.
345   *
346   * @param measurement The current measured State of the system.
347   */
348  public void reset(TrapezoidProfile.State measurement) {
349    m_controller.reset();
350    m_setpoint = measurement;
351  }
352
353  /**
354   * Reset the previous error and the integral term.
355   *
356   * @param measuredPosition The current measured position of the system.
357   * @param measuredVelocity The current measured velocity of the system.
358   */
359  public void reset(double measuredPosition, double measuredVelocity) {
360    reset(new TrapezoidProfile.State(measuredPosition, measuredVelocity));
361  }
362
363  /**
364   * Reset the previous error and the integral term.
365   *
366   * @param measuredPosition The current measured position of the system. The velocity is assumed to
367   *     be zero.
368   */
369  public void reset(double measuredPosition) {
370    reset(measuredPosition, 0.0);
371  }
372
373  @Override
374  public void initSendable(SendableBuilder builder) {
375    builder.setSmartDashboardType("ProfiledPIDController");
376    builder.addDoubleProperty("p", this::getP, this::setP);
377    builder.addDoubleProperty("i", this::getI, this::setI);
378    builder.addDoubleProperty("d", this::getD, this::setD);
379    builder.addDoubleProperty("goal", () -> getGoal().position, this::setGoal);
380  }
381}