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.wpilibj;
006
007import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam;
008
009import edu.wpi.first.hal.FRCNetComm.tResourceType;
010import edu.wpi.first.hal.HAL;
011import edu.wpi.first.hal.util.BoundaryException;
012import edu.wpi.first.math.filter.LinearFilter;
013import edu.wpi.first.util.sendable.Sendable;
014import edu.wpi.first.util.sendable.SendableBuilder;
015import edu.wpi.first.util.sendable.SendableRegistry;
016import java.util.concurrent.locks.ReentrantLock;
017
018/**
019 * Class implements a PID Control Loop.
020 *
021 * <p>Creates a separate thread which reads the given PIDSource and takes care of the integral
022 * calculations, as well as writing the given PIDOutput.
023 *
024 * <p>This feedback controller runs in discrete time, so time deltas are not used in the integral
025 * and derivative calculations. Therefore, the sample rate affects the controller's behavior for a
026 * given set of PID constants.
027 *
028 * @deprecated All APIs which use this have been deprecated.
029 */
030@Deprecated(since = "2020", forRemoval = true)
031public class PIDBase implements PIDInterface, PIDOutput, Sendable, AutoCloseable {
032  public static final double kDefaultPeriod = 0.05;
033  private static int instances;
034
035  // Factor for "proportional" control
036  @SuppressWarnings("MemberName")
037  private double m_P;
038
039  // Factor for "integral" control
040  @SuppressWarnings("MemberName")
041  private double m_I;
042
043  // Factor for "derivative" control
044  @SuppressWarnings("MemberName")
045  private double m_D;
046
047  // Factor for "feed forward" control
048  @SuppressWarnings("MemberName")
049  private double m_F;
050
051  // |maximum output|
052  private double m_maximumOutput = 1.0;
053
054  // |minimum output|
055  private double m_minimumOutput = -1.0;
056
057  // Maximum input - limit setpoint to this
058  private double m_maximumInput;
059
060  // Minimum input - limit setpoint to this
061  private double m_minimumInput;
062
063  // Input range - difference between maximum and minimum
064  private double m_inputRange;
065
066  // Do the endpoints wrap around? (e.g., absolute encoder)
067  private boolean m_continuous;
068
069  // Is the PID controller enabled
070  protected boolean m_enabled;
071
072  // The prior error (used to compute velocity)
073  private double m_prevError;
074
075  // The sum of the errors for use in the integral calc
076  private double m_totalError;
077
078  // The tolerance object used to check if on target
079  private Tolerance m_tolerance;
080
081  private double m_setpoint;
082  private double m_prevSetpoint;
083
084  private double m_result;
085
086  private LinearFilter m_filter;
087
088  protected ReentrantLock m_thisMutex = new ReentrantLock();
089
090  // Ensures when disable() is called, pidWrite() won't run if calculate()
091  // is already running at that time.
092  protected ReentrantLock m_pidWriteMutex = new ReentrantLock();
093
094  protected PIDSource m_pidInput;
095  protected PIDOutput m_pidOutput;
096  protected Timer m_setpointTimer;
097
098  /**
099   * Tolerance is the type of tolerance used to specify if the PID controller is on target.
100   *
101   * <p>The various implementations of this class such as PercentageTolerance and AbsoluteTolerance
102   * specify types of tolerance specifications to use.
103   */
104  public interface Tolerance {
105    boolean onTarget();
106  }
107
108  /** Used internally for when Tolerance hasn't been set. */
109  public static class NullTolerance implements Tolerance {
110    @Override
111    public boolean onTarget() {
112      throw new IllegalStateException("No tolerance value set when calling onTarget().");
113    }
114  }
115
116  public class PercentageTolerance implements Tolerance {
117    private final double m_percentage;
118
119    PercentageTolerance(double value) {
120      m_percentage = value;
121    }
122
123    @Override
124    public boolean onTarget() {
125      return Math.abs(getError()) < m_percentage / 100 * m_inputRange;
126    }
127  }
128
129  public class AbsoluteTolerance implements Tolerance {
130    private final double m_value;
131
132    AbsoluteTolerance(double value) {
133      m_value = value;
134    }
135
136    @Override
137    public boolean onTarget() {
138      return Math.abs(getError()) < m_value;
139    }
140  }
141
142  /**
143   * Allocate a PID object with the given constants for P, I, D, and F.
144   *
145   * @param Kp the proportional coefficient
146   * @param Ki the integral coefficient
147   * @param Kd the derivative coefficient
148   * @param Kf the feed forward term
149   * @param source The PIDSource object that is used to get values
150   * @param output The PIDOutput object that is set to the output percentage
151   */
152  @SuppressWarnings("ParameterName")
153  public PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output) {
154    requireNonNullParam(source, "PIDSource", "PIDBase");
155    requireNonNullParam(output, "output", "PIDBase");
156
157    m_setpointTimer = new Timer();
158    m_setpointTimer.start();
159
160    m_P = Kp;
161    m_I = Ki;
162    m_D = Kd;
163    m_F = Kf;
164
165    m_pidInput = source;
166    m_filter = LinearFilter.movingAverage(1);
167
168    m_pidOutput = output;
169
170    instances++;
171    HAL.report(tResourceType.kResourceType_PIDController, instances);
172    m_tolerance = new NullTolerance();
173    SendableRegistry.add(this, "PIDController", instances);
174  }
175
176  /**
177   * Allocate a PID object with the given constants for P, I, and D.
178   *
179   * @param Kp the proportional coefficient
180   * @param Ki the integral coefficient
181   * @param Kd the derivative coefficient
182   * @param source the PIDSource object that is used to get values
183   * @param output the PIDOutput object that is set to the output percentage
184   */
185  @SuppressWarnings("ParameterName")
186  public PIDBase(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output) {
187    this(Kp, Ki, Kd, 0.0, source, output);
188  }
189
190  @Override
191  public void close() {
192    SendableRegistry.remove(this);
193  }
194
195  /**
196   * Read the input, calculate the output accordingly, and write to the output. This should only be
197   * called by the PIDTask and is created during initialization.
198   */
199  @SuppressWarnings("LocalVariableName")
200  protected void calculate() {
201    if (m_pidInput == null || m_pidOutput == null) {
202      return;
203    }
204
205    boolean enabled;
206
207    m_thisMutex.lock();
208    try {
209      enabled = m_enabled;
210    } finally {
211      m_thisMutex.unlock();
212    }
213
214    if (enabled) {
215      double input;
216
217      // Storage for function inputs
218      PIDSourceType pidSourceType;
219      double P;
220      double I;
221      double D;
222      double feedForward = calculateFeedForward();
223      double minimumOutput;
224      double maximumOutput;
225
226      // Storage for function input-outputs
227      double prevError;
228      double error;
229      double totalError;
230
231      m_thisMutex.lock();
232      try {
233        input = m_filter.calculate(m_pidInput.pidGet());
234
235        pidSourceType = m_pidInput.getPIDSourceType();
236        P = m_P;
237        I = m_I;
238        D = m_D;
239        minimumOutput = m_minimumOutput;
240        maximumOutput = m_maximumOutput;
241
242        prevError = m_prevError;
243        error = getContinuousError(m_setpoint - input);
244        totalError = m_totalError;
245      } finally {
246        m_thisMutex.unlock();
247      }
248
249      // Storage for function outputs
250      double result;
251
252      if (pidSourceType.equals(PIDSourceType.kRate)) {
253        if (P != 0) {
254          totalError = clamp(totalError + error, minimumOutput / P, maximumOutput / P);
255        }
256
257        result = P * totalError + D * error + feedForward;
258      } else {
259        if (I != 0) {
260          totalError = clamp(totalError + error, minimumOutput / I, maximumOutput / I);
261        }
262
263        result = P * error + I * totalError + D * (error - prevError) + feedForward;
264      }
265
266      result = clamp(result, minimumOutput, maximumOutput);
267
268      // Ensures m_enabled check and pidWrite() call occur atomically
269      m_pidWriteMutex.lock();
270      m_thisMutex.lock();
271      try {
272        if (m_enabled) {
273          // Don't block other PIDController operations on pidWrite()
274          m_thisMutex.unlock();
275
276          m_pidOutput.pidWrite(result);
277        }
278      } finally {
279        if (!m_enabled) {
280          m_thisMutex.unlock();
281        }
282        m_pidWriteMutex.unlock();
283      }
284
285      m_thisMutex.lock();
286      try {
287        m_prevError = error;
288        m_totalError = totalError;
289        m_result = result;
290      } finally {
291        m_thisMutex.unlock();
292      }
293    }
294  }
295
296  /**
297   * Calculate the feed forward term.
298   *
299   * <p>Both of the provided feed forward calculations are velocity feed forwards. If a different
300   * feed forward calculation is desired, the user can override this function and provide his or her
301   * own. This function does no synchronization because the PIDController class only calls it in
302   * synchronized code, so be careful if calling it oneself.
303   *
304   * <p>If a velocity PID controller is being used, the F term should be set to 1 over the maximum
305   * setpoint for the output. If a position PID controller is being used, the F term should be set
306   * to 1 over the maximum speed for the output measured in setpoint units per this controller's
307   * update period (see the default period in this class's constructor).
308   *
309   * @return The feedforward value.
310   */
311  protected double calculateFeedForward() {
312    if (m_pidInput.getPIDSourceType().equals(PIDSourceType.kRate)) {
313      return m_F * getSetpoint();
314    } else {
315      double temp = m_F * getDeltaSetpoint();
316      m_prevSetpoint = m_setpoint;
317      m_setpointTimer.reset();
318      return temp;
319    }
320  }
321
322  /**
323   * Set the PID Controller gain parameters. Set the proportional, integral, and differential
324   * coefficients.
325   *
326   * @param p Proportional coefficient
327   * @param i Integral coefficient
328   * @param d Differential coefficient
329   */
330  @Override
331  @SuppressWarnings("ParameterName")
332  public void setPID(double p, double i, double d) {
333    m_thisMutex.lock();
334    try {
335      m_P = p;
336      m_I = i;
337      m_D = d;
338    } finally {
339      m_thisMutex.unlock();
340    }
341  }
342
343  /**
344   * Set the PID Controller gain parameters. Set the proportional, integral, and differential
345   * coefficients.
346   *
347   * @param p Proportional coefficient
348   * @param i Integral coefficient
349   * @param d Differential coefficient
350   * @param f Feed forward coefficient
351   */
352  @SuppressWarnings("ParameterName")
353  public void setPID(double p, double i, double d, double f) {
354    m_thisMutex.lock();
355    try {
356      m_P = p;
357      m_I = i;
358      m_D = d;
359      m_F = f;
360    } finally {
361      m_thisMutex.unlock();
362    }
363  }
364
365  /**
366   * Set the Proportional coefficient of the PID controller gain.
367   *
368   * @param p Proportional coefficient
369   */
370  @SuppressWarnings("ParameterName")
371  public void setP(double p) {
372    m_thisMutex.lock();
373    try {
374      m_P = p;
375    } finally {
376      m_thisMutex.unlock();
377    }
378  }
379
380  /**
381   * Set the Integral coefficient of the PID controller gain.
382   *
383   * @param i Integral coefficient
384   */
385  @SuppressWarnings("ParameterName")
386  public void setI(double i) {
387    m_thisMutex.lock();
388    try {
389      m_I = i;
390    } finally {
391      m_thisMutex.unlock();
392    }
393  }
394
395  /**
396   * Set the Differential coefficient of the PID controller gain.
397   *
398   * @param d differential coefficient
399   */
400  @SuppressWarnings("ParameterName")
401  public void setD(double d) {
402    m_thisMutex.lock();
403    try {
404      m_D = d;
405    } finally {
406      m_thisMutex.unlock();
407    }
408  }
409
410  /**
411   * Set the Feed forward coefficient of the PID controller gain.
412   *
413   * @param f feed forward coefficient
414   */
415  @SuppressWarnings("ParameterName")
416  public void setF(double f) {
417    m_thisMutex.lock();
418    try {
419      m_F = f;
420    } finally {
421      m_thisMutex.unlock();
422    }
423  }
424
425  /**
426   * Get the Proportional coefficient.
427   *
428   * @return proportional coefficient
429   */
430  @Override
431  public double getP() {
432    m_thisMutex.lock();
433    try {
434      return m_P;
435    } finally {
436      m_thisMutex.unlock();
437    }
438  }
439
440  /**
441   * Get the Integral coefficient.
442   *
443   * @return integral coefficient
444   */
445  @Override
446  public double getI() {
447    m_thisMutex.lock();
448    try {
449      return m_I;
450    } finally {
451      m_thisMutex.unlock();
452    }
453  }
454
455  /**
456   * Get the Differential coefficient.
457   *
458   * @return differential coefficient
459   */
460  @Override
461  public double getD() {
462    m_thisMutex.lock();
463    try {
464      return m_D;
465    } finally {
466      m_thisMutex.unlock();
467    }
468  }
469
470  /**
471   * Get the Feed forward coefficient.
472   *
473   * @return feed forward coefficient
474   */
475  public double getF() {
476    m_thisMutex.lock();
477    try {
478      return m_F;
479    } finally {
480      m_thisMutex.unlock();
481    }
482  }
483
484  /**
485   * Return the current PID result This is always centered on zero and constrained the the max and
486   * min outs.
487   *
488   * @return the latest calculated output
489   */
490  public double get() {
491    m_thisMutex.lock();
492    try {
493      return m_result;
494    } finally {
495      m_thisMutex.unlock();
496    }
497  }
498
499  /**
500   * Set the PID controller to consider the input to be continuous, Rather then using the max and
501   * min input range as constraints, it considers them to be the same point and automatically
502   * calculates the shortest route to the setpoint.
503   *
504   * @param continuous Set to true turns on continuous, false turns off continuous
505   */
506  public void setContinuous(boolean continuous) {
507    if (continuous && m_inputRange <= 0) {
508      throw new IllegalStateException("No input range set when calling setContinuous().");
509    }
510    m_thisMutex.lock();
511    try {
512      m_continuous = continuous;
513    } finally {
514      m_thisMutex.unlock();
515    }
516  }
517
518  /**
519   * Set the PID controller to consider the input to be continuous, Rather then using the max and
520   * min input range as constraints, it considers them to be the same point and automatically
521   * calculates the shortest route to the setpoint.
522   */
523  public void setContinuous() {
524    setContinuous(true);
525  }
526
527  /**
528   * Sets the maximum and minimum values expected from the input and setpoint.
529   *
530   * @param minimumInput the minimum value expected from the input
531   * @param maximumInput the maximum value expected from the input
532   */
533  public void setInputRange(double minimumInput, double maximumInput) {
534    m_thisMutex.lock();
535    try {
536      if (minimumInput > maximumInput) {
537        throw new BoundaryException("Lower bound is greater than upper bound");
538      }
539      m_minimumInput = minimumInput;
540      m_maximumInput = maximumInput;
541      m_inputRange = maximumInput - minimumInput;
542    } finally {
543      m_thisMutex.unlock();
544    }
545
546    setSetpoint(m_setpoint);
547  }
548
549  /**
550   * Sets the minimum and maximum values to write.
551   *
552   * @param minimumOutput the minimum percentage to write to the output
553   * @param maximumOutput the maximum percentage to write to the output
554   */
555  public void setOutputRange(double minimumOutput, double maximumOutput) {
556    m_thisMutex.lock();
557    try {
558      if (minimumOutput > maximumOutput) {
559        throw new BoundaryException("Lower bound is greater than upper bound");
560      }
561      m_minimumOutput = minimumOutput;
562      m_maximumOutput = maximumOutput;
563    } finally {
564      m_thisMutex.unlock();
565    }
566  }
567
568  /**
569   * Set the setpoint for the PIDController.
570   *
571   * @param setpoint the desired setpoint
572   */
573  @Override
574  public void setSetpoint(double setpoint) {
575    m_thisMutex.lock();
576    try {
577      if (m_maximumInput > m_minimumInput) {
578        if (setpoint > m_maximumInput) {
579          m_setpoint = m_maximumInput;
580        } else if (setpoint < m_minimumInput) {
581          m_setpoint = m_minimumInput;
582        } else {
583          m_setpoint = setpoint;
584        }
585      } else {
586        m_setpoint = setpoint;
587      }
588    } finally {
589      m_thisMutex.unlock();
590    }
591  }
592
593  /**
594   * Returns the current setpoint of the PIDController.
595   *
596   * @return the current setpoint
597   */
598  @Override
599  public double getSetpoint() {
600    m_thisMutex.lock();
601    try {
602      return m_setpoint;
603    } finally {
604      m_thisMutex.unlock();
605    }
606  }
607
608  /**
609   * Returns the change in setpoint over time of the PIDController.
610   *
611   * @return the change in setpoint over time
612   */
613  public double getDeltaSetpoint() {
614    m_thisMutex.lock();
615    try {
616      return (m_setpoint - m_prevSetpoint) / m_setpointTimer.get();
617    } finally {
618      m_thisMutex.unlock();
619    }
620  }
621
622  /**
623   * Returns the current difference of the input from the setpoint.
624   *
625   * @return the current error
626   */
627  @Override
628  public double getError() {
629    m_thisMutex.lock();
630    try {
631      return getContinuousError(getSetpoint() - m_filter.calculate(m_pidInput.pidGet()));
632    } finally {
633      m_thisMutex.unlock();
634    }
635  }
636
637  /**
638   * Returns the current difference of the error over the past few iterations. You can specify the
639   * number of iterations to average with setToleranceBuffer() (defaults to 1). getAvgError() is
640   * used for the onTarget() function.
641   *
642   * @return the current average of the error
643   * @deprecated Use getError(), which is now already filtered.
644   */
645  @Deprecated
646  public double getAvgError() {
647    m_thisMutex.lock();
648    try {
649      return getError();
650    } finally {
651      m_thisMutex.unlock();
652    }
653  }
654
655  /**
656   * Sets what type of input the PID controller will use.
657   *
658   * @param pidSource the type of input
659   */
660  public void setPIDSourceType(PIDSourceType pidSource) {
661    m_pidInput.setPIDSourceType(pidSource);
662  }
663
664  /**
665   * Returns the type of input the PID controller is using.
666   *
667   * @return the PID controller input type
668   */
669  public PIDSourceType getPIDSourceType() {
670    return m_pidInput.getPIDSourceType();
671  }
672
673  /**
674   * Set the PID tolerance using a Tolerance object. Tolerance can be specified as a percentage of
675   * the range or as an absolute value. The Tolerance object encapsulates those options in an
676   * object. Use it by creating the type of tolerance that you want to use: setTolerance(new
677   * PIDController.AbsoluteTolerance(0.1))
678   *
679   * @param tolerance A tolerance object of the right type, e.g. PercentTolerance or
680   *     AbsoluteTolerance
681   * @deprecated Use setPercentTolerance() instead.
682   */
683  @Deprecated
684  public void setTolerance(Tolerance tolerance) {
685    m_tolerance = tolerance;
686  }
687
688  /**
689   * Set the absolute error which is considered tolerable for use with OnTarget.
690   *
691   * @param absvalue absolute error which is tolerable in the units of the input object
692   */
693  public void setAbsoluteTolerance(double absvalue) {
694    m_thisMutex.lock();
695    try {
696      m_tolerance = new AbsoluteTolerance(absvalue);
697    } finally {
698      m_thisMutex.unlock();
699    }
700  }
701
702  /**
703   * Set the percentage error which is considered tolerable for use with OnTarget. (Input of 15.0 =
704   * 15 percent)
705   *
706   * @param percentage percent error which is tolerable
707   */
708  public void setPercentTolerance(double percentage) {
709    m_thisMutex.lock();
710    try {
711      m_tolerance = new PercentageTolerance(percentage);
712    } finally {
713      m_thisMutex.unlock();
714    }
715  }
716
717  /**
718   * Set the number of previous error samples to average for tolerancing. When determining whether a
719   * mechanism is on target, the user may want to use a rolling average of previous measurements
720   * instead of a precise position or velocity. This is useful for noisy sensors which return a few
721   * erroneous measurements when the mechanism is on target. However, the mechanism will not
722   * register as on target for at least the specified bufLength cycles.
723   *
724   * @param bufLength Number of previous cycles to average.
725   * @deprecated Use a LinearFilter as the input.
726   */
727  @Deprecated
728  public void setToleranceBuffer(int bufLength) {
729    m_thisMutex.lock();
730    try {
731      m_filter = LinearFilter.movingAverage(bufLength);
732    } finally {
733      m_thisMutex.unlock();
734    }
735  }
736
737  /**
738   * Return true if the error is within the percentage of the total input range, determined by
739   * setTolerance. This assumes that the maximum and minimum input were set using setInput.
740   *
741   * @return true if the error is less than the tolerance
742   */
743  public boolean onTarget() {
744    m_thisMutex.lock();
745    try {
746      return m_tolerance.onTarget();
747    } finally {
748      m_thisMutex.unlock();
749    }
750  }
751
752  /** Reset the previous error, the integral term, and disable the controller. */
753  @Override
754  public void reset() {
755    m_thisMutex.lock();
756    try {
757      m_prevError = 0;
758      m_totalError = 0;
759      m_result = 0;
760    } finally {
761      m_thisMutex.unlock();
762    }
763  }
764
765  /**
766   * Passes the output directly to setSetpoint().
767   *
768   * <p>PIDControllers can be nested by passing a PIDController as another PIDController's output.
769   * In that case, the output of the parent controller becomes the input (i.e., the reference) of
770   * the child.
771   *
772   * <p>It is the caller's responsibility to put the data into a valid form for setSetpoint().
773   */
774  @Override
775  public void pidWrite(double output) {
776    setSetpoint(output);
777  }
778
779  @Override
780  public void initSendable(SendableBuilder builder) {
781    builder.setSmartDashboardType("PIDController");
782    builder.setSafeState(this::reset);
783    builder.addDoubleProperty("p", this::getP, this::setP);
784    builder.addDoubleProperty("i", this::getI, this::setI);
785    builder.addDoubleProperty("d", this::getD, this::setD);
786    builder.addDoubleProperty("f", this::getF, this::setF);
787    builder.addDoubleProperty("setpoint", this::getSetpoint, this::setSetpoint);
788  }
789
790  /**
791   * Wraps error around for continuous inputs. The original error is returned if continuous mode is
792   * disabled. This is an unsynchronized function.
793   *
794   * @param error The current error of the PID controller.
795   * @return Error for continuous inputs.
796   */
797  protected double getContinuousError(double error) {
798    if (m_continuous && m_inputRange > 0) {
799      error %= m_inputRange;
800      if (Math.abs(error) > m_inputRange / 2) {
801        if (error > 0) {
802          return error - m_inputRange;
803        } else {
804          return error + m_inputRange;
805        }
806      }
807    }
808
809    return error;
810  }
811
812  private static double clamp(double value, double low, double high) {
813    return Math.max(low, Math.min(value, high));
814  }
815}