Class AbstractPID<T extends edu.wpi.first.wpilibj.PIDSource,​V extends java.lang.Number>

  • Type Parameters:
    T - the type of sensor used as input to this PID system.
    V - the type of value read from the sensor used as input to this PID system.
    All Implemented Interfaces:
    PID<T,​V>
    Direct Known Subclasses:
    PIDulum, SimplePID, VelocityController

    public abstract class AbstractPID<T extends edu.wpi.first.wpilibj.PIDSource,​V extends java.lang.Number>
    extends java.lang.Object
    implements PID<T,​V>
    A PID loop, which uses a PIDSrc and a set of constants to iteratively determine output values with which a system can reach and maintain a target value.
    • Constructor Summary

      Constructors 
      Constructor Description
      AbstractPID​(PIDSrc<T,​V> source, float deadband, int deadbandPeriod, java.util.concurrent.TimeUnit deadbandUnit, float kP, float kI, float kD)
      Create a new AbstractPID instance.
    • Method Summary

      All Methods Instance Methods Abstract Methods Concrete Methods 
      Modifier and Type Method Description
      boolean atTarget()
      Check if this PID has reached its target value.
      void clear()
      Reset the state of this PID loop.
      float getkD()
      Get the Derivative constant for this PID.
      float getkI()
      Get the Integral constant for this PID.
      float getkP()
      Get the Proportional constant for this PID.
      PIDSrc<T,​V> getSrc()
      Get the source sensor of this PID.
      abstract V pid​(V target)
      Iterate the PID loop.
      void setkD​(float kD)
      Set the Derivative constant for this PID.
      void setkI​(float kI)
      Set the Integral constant for this PID.
      void setkP​(float kP)
      Set the Proportional constant for this PID.
      • Methods inherited from class java.lang.Object

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

      • source

        protected final PIDSrc<T extends edu.wpi.first.wpilibj.PIDSource,​V extends java.lang.Number> source
        A PIDSrc sensor.
      • deadband

        protected volatile float deadband
      • kP

        protected volatile float kP
      • kI

        protected volatile float kI
      • kD

        protected volatile float kD
      • integralError

        protected volatile float integralError
      • prevError

        protected volatile float prevError
      • deltaError

        protected volatile float deltaError
      • deadbandPeriod

        protected volatile int deadbandPeriod
      • deadbandUnit

        protected volatile java.util.concurrent.TimeUnit deadbandUnit
      • lastTimeNotAtTarget

        protected volatile long lastTimeNotAtTarget
    • Constructor Detail

      • AbstractPID

        public AbstractPID​(PIDSrc<T,​V> source,
                           float deadband,
                           int deadbandPeriod,
                           java.util.concurrent.TimeUnit deadbandUnit,
                           float kP,
                           float kI,
                           float kD)
        Create a new AbstractPID instance.
        Parameters:
        source - the PIDSrc source sensor
        deadband - filter value - do not act when current error is within this bound. This can be disabled by passing a negative value
        deadbandPeriod - the amount of time to remain within acceptable error of the target value before claiming to actually be at the target
        deadbandUnit - the units for deadbandPeriod
        kP - P constant
        kI - I constant
        kD - D constant
    • Method Detail

      • clear

        public final void clear()
        Reset the state of this PID loop.
        Specified by:
        clear in interface PID<T extends edu.wpi.first.wpilibj.PIDSource,​V extends java.lang.Number>
      • pid

        public abstract V pid​(V target)
        Iterate the PID loop.
        Specified by:
        pid in interface PID<T extends edu.wpi.first.wpilibj.PIDSource,​V extends java.lang.Number>
        Parameters:
        target - the desired target value. Units depend on the context of this PID
        Returns:
        the output value to set to eg a SpeedController to reach the specified target
      • getSrc

        public final PIDSrc<T,​V> getSrc()
        Get the source sensor of this PID.
        Specified by:
        getSrc in interface PID<T extends edu.wpi.first.wpilibj.PIDSource,​V extends java.lang.Number>
        Returns:
        the PIDSrc (PID source sensor) used by this PID loop
      • atTarget

        public final boolean atTarget()
        Check if this PID has reached its target value.
        Specified by:
        atTarget in interface PID<T extends edu.wpi.first.wpilibj.PIDSource,​V extends java.lang.Number>
        Returns:
        whether this PID loop has reached the specified target value
      • setkP

        public void setkP​(float kP)
        Set the Proportional constant for this PID.
        Specified by:
        setkP in interface PID<T extends edu.wpi.first.wpilibj.PIDSource,​V extends java.lang.Number>
        Parameters:
        kP - the Proportional constant.
      • getkP

        public float getkP()
        Get the Proportional constant for this PID.
        Specified by:
        getkP in interface PID<T extends edu.wpi.first.wpilibj.PIDSource,​V extends java.lang.Number>
        Returns:
        the Proportional constant.
      • setkI

        public void setkI​(float kI)
        Set the Integral constant for this PID.
        Specified by:
        setkI in interface PID<T extends edu.wpi.first.wpilibj.PIDSource,​V extends java.lang.Number>
        Parameters:
        kI - the Integral constant.
      • getkI

        public float getkI()
        Get the Integral constant for this PID.
        Specified by:
        getkI in interface PID<T extends edu.wpi.first.wpilibj.PIDSource,​V extends java.lang.Number>
        Returns:
        the Integral constant.
      • setkD

        public void setkD​(float kD)
        Set the Derivative constant for this PID.
        Specified by:
        setkD in interface PID<T extends edu.wpi.first.wpilibj.PIDSource,​V extends java.lang.Number>
        Parameters:
        kD - the Derivative constant.
      • getkD

        public float getkD()
        Get the Derivative constant for this PID.
        Specified by:
        getkD in interface PID<T extends edu.wpi.first.wpilibj.PIDSource,​V extends java.lang.Number>
        Returns:
        the Derivative constant.