Class PIDBase

java.lang.Object
edu.wpi.first.wpilibj.PIDBase
All Implemented Interfaces:
Sendable, PIDInterface, PIDOutput, AutoCloseable
Direct Known Subclasses:
PIDController

@Deprecated(since="2020",
            forRemoval=true)
public class PIDBase
extends Object
implements PIDInterface, PIDOutput, Sendable, AutoCloseable
Deprecated, for removal: This API element is subject to removal in a future version.
All APIs which use this have been deprecated.
Class implements a PID Control Loop.

Creates a separate thread which reads the given PIDSource and takes care of the integral calculations, as well as writing the given PIDOutput.

This feedback controller runs in discrete time, so time deltas are not used in the integral and derivative calculations. Therefore, the sample rate affects the controller's behavior for a given set of PID constants.

  • Nested Class Summary

    Nested Classes 
    Modifier and Type Class Description
    class  PIDBase.AbsoluteTolerance
    Deprecated, for removal: This API element is subject to removal in a future version.
     
    static class  PIDBase.NullTolerance
    Deprecated, for removal: This API element is subject to removal in a future version.
    Used internally for when Tolerance hasn't been set.
    class  PIDBase.PercentageTolerance
    Deprecated, for removal: This API element is subject to removal in a future version.
     
    static interface  PIDBase.Tolerance
    Deprecated, for removal: This API element is subject to removal in a future version.
    Tolerance is the type of tolerance used to specify if the PID controller is on target.
  • Field Summary

    Fields 
    Modifier and Type Field Description
    static double kDefaultPeriod
    Deprecated, for removal: This API element is subject to removal in a future version.
     
    protected boolean m_enabled
    Deprecated, for removal: This API element is subject to removal in a future version.
     
    protected PIDSource m_pidInput
    Deprecated, for removal: This API element is subject to removal in a future version.
     
    protected PIDOutput m_pidOutput
    Deprecated, for removal: This API element is subject to removal in a future version.
     
    protected ReentrantLock m_pidWriteMutex
    Deprecated, for removal: This API element is subject to removal in a future version.
     
    protected Timer m_setpointTimer
    Deprecated, for removal: This API element is subject to removal in a future version.
     
    protected ReentrantLock m_thisMutex
    Deprecated, for removal: This API element is subject to removal in a future version.
     
  • Constructor Summary

    Constructors 
    Constructor Description
    PIDBase​(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Allocate a PID object with the given constants for P, I, D, and F.
    PIDBase​(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Allocate a PID object with the given constants for P, I, and D.
  • Method Summary

    Modifier and Type Method Description
    protected void calculate()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Read the input, calculate the output accordingly, and write to the output.
    protected double calculateFeedForward()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Calculate the feed forward term.
    void close()
    Deprecated, for removal: This API element is subject to removal in a future version.
     
    double get()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Return the current PID result This is always centered on zero and constrained the the max and min outs.
    double getAvgError()
    Deprecated.
    Use getError(), which is now already filtered.
    protected double getContinuousError​(double error)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Wraps error around for continuous inputs.
    double getD()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Get the Differential coefficient.
    double getDeltaSetpoint()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Returns the change in setpoint over time of the PIDController.
    double getError()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Returns the current difference of the input from the setpoint.
    double getF()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Get the Feed forward coefficient.
    double getI()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Get the Integral coefficient.
    double getP()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Get the Proportional coefficient.
    PIDSourceType getPIDSourceType()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Returns the type of input the PID controller is using.
    double getSetpoint()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Returns the current setpoint of the PIDController.
    void initSendable​(SendableBuilder builder)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Initializes this Sendable object.
    boolean onTarget()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Return true if the error is within the percentage of the total input range, determined by setTolerance.
    void pidWrite​(double output)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Passes the output directly to setSetpoint().
    void reset()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Reset the previous error, the integral term, and disable the controller.
    void setAbsoluteTolerance​(double absvalue)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Set the absolute error which is considered tolerable for use with OnTarget.
    void setContinuous()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Set the PID controller to consider the input to be continuous, Rather then using the max and min input range as constraints, it considers them to be the same point and automatically calculates the shortest route to the setpoint.
    void setContinuous​(boolean continuous)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Set the PID controller to consider the input to be continuous, Rather then using the max and min input range as constraints, it considers them to be the same point and automatically calculates the shortest route to the setpoint.
    void setD​(double d)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Set the Differential coefficient of the PID controller gain.
    void setF​(double f)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Set the Feed forward coefficient of the PID controller gain.
    void setI​(double i)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Set the Integral coefficient of the PID controller gain.
    void setInputRange​(double minimumInput, double maximumInput)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Sets the maximum and minimum values expected from the input and setpoint.
    void setOutputRange​(double minimumOutput, double maximumOutput)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Sets the minimum and maximum values to write.
    void setP​(double p)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Set the Proportional coefficient of the PID controller gain.
    void setPercentTolerance​(double percentage)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Set the percentage error which is considered tolerable for use with OnTarget.
    void setPID​(double p, double i, double d)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Set the PID Controller gain parameters.
    void setPID​(double p, double i, double d, double f)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Set the PID Controller gain parameters.
    void setPIDSourceType​(PIDSourceType pidSource)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Sets what type of input the PID controller will use.
    void setSetpoint​(double setpoint)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Set the setpoint for the PIDController.
    void setTolerance​(PIDBase.Tolerance tolerance)
    Deprecated.
    Use setPercentTolerance() instead.
    void setToleranceBuffer​(int bufLength)
    Deprecated.
    Use a LinearFilter as the input.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Field Details

  • Constructor Details

    • PIDBase

      public PIDBase​(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Allocate a PID object with the given constants for P, I, D, and F.
      Parameters:
      Kp - the proportional coefficient
      Ki - the integral coefficient
      Kd - the derivative coefficient
      Kf - the feed forward term
      source - The PIDSource object that is used to get values
      output - The PIDOutput object that is set to the output percentage
    • PIDBase

      public PIDBase​(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Allocate a PID object with the given constants for P, I, and D.
      Parameters:
      Kp - the proportional coefficient
      Ki - the integral coefficient
      Kd - the derivative coefficient
      source - the PIDSource object that is used to get values
      output - the PIDOutput object that is set to the output percentage
  • Method Details

    • close

      public void close()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Specified by:
      close in interface AutoCloseable
    • calculate

      protected void calculate()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Read the input, calculate the output accordingly, and write to the output. This should only be called by the PIDTask and is created during initialization.
    • calculateFeedForward

      protected double calculateFeedForward()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Calculate the feed forward term.

      Both of the provided feed forward calculations are velocity feed forwards. If a different feed forward calculation is desired, the user can override this function and provide his or her own. This function does no synchronization because the PIDController class only calls it in synchronized code, so be careful if calling it oneself.

      If a velocity PID controller is being used, the F term should be set to 1 over the maximum setpoint for the output. If a position PID controller is being used, the F term should be set to 1 over the maximum speed for the output measured in setpoint units per this controller's update period (see the default period in this class's constructor).

      Returns:
      The feedforward value.
    • setPID

      public void setPID​(double p, double i, double d)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set the PID Controller gain parameters. Set the proportional, integral, and differential coefficients.
      Specified by:
      setPID in interface PIDInterface
      Parameters:
      p - Proportional coefficient
      i - Integral coefficient
      d - Differential coefficient
    • setPID

      public void setPID​(double p, double i, double d, double f)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set the PID Controller gain parameters. Set the proportional, integral, and differential coefficients.
      Parameters:
      p - Proportional coefficient
      i - Integral coefficient
      d - Differential coefficient
      f - Feed forward coefficient
    • setP

      public void setP​(double p)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set the Proportional coefficient of the PID controller gain.
      Parameters:
      p - Proportional coefficient
    • setI

      public void setI​(double i)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set the Integral coefficient of the PID controller gain.
      Parameters:
      i - Integral coefficient
    • setD

      public void setD​(double d)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set the Differential coefficient of the PID controller gain.
      Parameters:
      d - differential coefficient
    • setF

      public void setF​(double f)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set the Feed forward coefficient of the PID controller gain.
      Parameters:
      f - feed forward coefficient
    • getP

      public double getP()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Get the Proportional coefficient.
      Specified by:
      getP in interface PIDInterface
      Returns:
      proportional coefficient
    • getI

      public double getI()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Get the Integral coefficient.
      Specified by:
      getI in interface PIDInterface
      Returns:
      integral coefficient
    • getD

      public double getD()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Get the Differential coefficient.
      Specified by:
      getD in interface PIDInterface
      Returns:
      differential coefficient
    • getF

      public double getF()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Get the Feed forward coefficient.
      Returns:
      feed forward coefficient
    • get

      public double get()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Return the current PID result This is always centered on zero and constrained the the max and min outs.
      Returns:
      the latest calculated output
    • setContinuous

      public void setContinuous​(boolean continuous)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set the PID controller to consider the input to be continuous, Rather then using the max and min input range as constraints, it considers them to be the same point and automatically calculates the shortest route to the setpoint.
      Parameters:
      continuous - Set to true turns on continuous, false turns off continuous
    • setContinuous

      public void setContinuous()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set the PID controller to consider the input to be continuous, Rather then using the max and min input range as constraints, it considers them to be the same point and automatically calculates the shortest route to the setpoint.
    • setInputRange

      public void setInputRange​(double minimumInput, double maximumInput)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Sets the maximum and minimum values expected from the input and setpoint.
      Parameters:
      minimumInput - the minimum value expected from the input
      maximumInput - the maximum value expected from the input
    • setOutputRange

      public void setOutputRange​(double minimumOutput, double maximumOutput)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Sets the minimum and maximum values to write.
      Parameters:
      minimumOutput - the minimum percentage to write to the output
      maximumOutput - the maximum percentage to write to the output
    • setSetpoint

      public void setSetpoint​(double setpoint)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set the setpoint for the PIDController.
      Specified by:
      setSetpoint in interface PIDInterface
      Parameters:
      setpoint - the desired setpoint
    • getSetpoint

      public double getSetpoint()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Returns the current setpoint of the PIDController.
      Specified by:
      getSetpoint in interface PIDInterface
      Returns:
      the current setpoint
    • getDeltaSetpoint

      public double getDeltaSetpoint()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Returns the change in setpoint over time of the PIDController.
      Returns:
      the change in setpoint over time
    • getError

      public double getError()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Returns the current difference of the input from the setpoint.
      Specified by:
      getError in interface PIDInterface
      Returns:
      the current error
    • getAvgError

      @Deprecated public double getAvgError()
      Deprecated.
      Use getError(), which is now already filtered.
      Returns the current difference of the error over the past few iterations. You can specify the number of iterations to average with setToleranceBuffer() (defaults to 1). getAvgError() is used for the onTarget() function.
      Returns:
      the current average of the error
    • setPIDSourceType

      public void setPIDSourceType​(PIDSourceType pidSource)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Sets what type of input the PID controller will use.
      Parameters:
      pidSource - the type of input
    • getPIDSourceType

      Deprecated, for removal: This API element is subject to removal in a future version.
      Returns the type of input the PID controller is using.
      Returns:
      the PID controller input type
    • setTolerance

      @Deprecated public void setTolerance​(PIDBase.Tolerance tolerance)
      Deprecated.
      Use setPercentTolerance() instead.
      Set the PID tolerance using a Tolerance object. Tolerance can be specified as a percentage of the range or as an absolute value. The Tolerance object encapsulates those options in an object. Use it by creating the type of tolerance that you want to use: setTolerance(new PIDController.AbsoluteTolerance(0.1))
      Parameters:
      tolerance - A tolerance object of the right type, e.g. PercentTolerance or AbsoluteTolerance
    • setAbsoluteTolerance

      public void setAbsoluteTolerance​(double absvalue)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set the absolute error which is considered tolerable for use with OnTarget.
      Parameters:
      absvalue - absolute error which is tolerable in the units of the input object
    • setPercentTolerance

      public void setPercentTolerance​(double percentage)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Set the percentage error which is considered tolerable for use with OnTarget. (Input of 15.0 = 15 percent)
      Parameters:
      percentage - percent error which is tolerable
    • setToleranceBuffer

      @Deprecated public void setToleranceBuffer​(int bufLength)
      Deprecated.
      Use a LinearFilter as the input.
      Set the number of previous error samples to average for tolerancing. When determining whether a mechanism is on target, the user may want to use a rolling average of previous measurements instead of a precise position or velocity. This is useful for noisy sensors which return a few erroneous measurements when the mechanism is on target. However, the mechanism will not register as on target for at least the specified bufLength cycles.
      Parameters:
      bufLength - Number of previous cycles to average.
    • onTarget

      public boolean onTarget()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Return true if the error is within the percentage of the total input range, determined by setTolerance. This assumes that the maximum and minimum input were set using setInput.
      Returns:
      true if the error is less than the tolerance
    • reset

      public void reset()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Reset the previous error, the integral term, and disable the controller.
      Specified by:
      reset in interface PIDInterface
    • pidWrite

      public void pidWrite​(double output)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Passes the output directly to setSetpoint().

      PIDControllers can be nested by passing a PIDController as another PIDController's output. In that case, the output of the parent controller becomes the input (i.e., the reference) of the child.

      It is the caller's responsibility to put the data into a valid form for setSetpoint().

      Specified by:
      pidWrite in interface PIDOutput
      Parameters:
      output - the value calculated by PIDController
    • initSendable

      public void initSendable​(SendableBuilder builder)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Description copied from interface: Sendable
      Initializes this Sendable object.
      Specified by:
      initSendable in interface Sendable
      Parameters:
      builder - sendable builder
    • getContinuousError

      protected double getContinuousError​(double error)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Wraps error around for continuous inputs. The original error is returned if continuous mode is disabled. This is an unsynchronized function.
      Parameters:
      error - The current error of the PID controller.
      Returns:
      Error for continuous inputs.