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