Class VelocityController

  • All Implemented Interfaces:
    PID<edu.wpi.first.wpilibj.pidwrappers.PIDEncoder,​java.lang.Float>, PIDRateValueSrc<edu.wpi.first.wpilibj.pidwrappers.PIDEncoder>, PIDSrc<edu.wpi.first.wpilibj.pidwrappers.PIDEncoder,​java.lang.Float>, ComposedComponent<java.lang.Object>, edu.wpi.first.wpilibj.PIDSource, edu.wpi.first.wpilibj.SpeedController
    Direct Known Subclasses:
    TractionController

    public class VelocityController
    extends AbstractPID<edu.wpi.first.wpilibj.pidwrappers.PIDEncoder,​java.lang.Float>
    implements edu.wpi.first.wpilibj.SpeedController, PIDRateValueSrc<edu.wpi.first.wpilibj.pidwrappers.PIDEncoder>, ComposedComponent<java.lang.Object>
    A SpeedController implementation which treats its input and output values as proportions of PID velocity targets, using an Encoder to measure the rotational rate of the associated SpeedController (ex Talon, Victor, Jaguar). Intended usage is to call set(double) whenever the target value changes OR a PID loop iteration is desired. pid(Float) will only return the adjusted value for the next PID iteration; this value represents an actual motor output value, but is not automatically applied to the backing SpeedController instance.
    • Constructor Summary

      Constructors 
      Constructor Description
      VelocityController​(edu.wpi.first.wpilibj.SpeedController speedController, PIDRateValueSrc<edu.wpi.first.wpilibj.pidwrappers.PIDEncoder> encoderPidSrc, float maxRotationalRate, float kP, float kI, float kD, float maxIntegralError, float deadband)
      Construct a new VelocityController instance.
      VelocityController​(edu.wpi.first.wpilibj.SpeedController speedController, edu.wpi.first.wpilibj.pidwrappers.PIDEncoder encoder, float maxRotationalRate, float kP, float kI, float kD, float maxIntegralError, float deadband)
      Construct a new VelocityController instance.
    • Method Summary

      All Methods Instance Methods Concrete Methods 
      Modifier and Type Method Description
      void disable()
      Disable this VelocityController.
      double get()
      Get the target rotational rate proportion which this VelocityController is set to.
      java.util.Collection<java.lang.Object> getComposedComponents()
      Get the composed components within this one.
      boolean getInverted()  
      edu.wpi.first.wpilibj.PIDSourceType getPIDSourceType()  
      java.lang.Float getPIDValue()
      Get the measured value of the sensor behind this PIDSrc.
      java.lang.Float getRate()
      Get the rate measured by this sensor.
      edu.wpi.first.wpilibj.pidwrappers.PIDEncoder getSensor()
      Get the sensor behind this PIDSrc.
      java.lang.Float pid​(java.lang.Float target)
      Iterate the PID loop.
      void set​(double v)
      Set the target rotational rate of this VelocityController.
      void setInverted​(boolean inverted)  
      void setPIDSourceType​(edu.wpi.first.wpilibj.PIDSourceType pidSourceType)  
      void stopMotor()  
      • Methods inherited from class java.lang.Object

        clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
      • Methods inherited from interface ca.team3161.lib.robot.pid.PIDSrc

        pidGet
      • Methods inherited from interface edu.wpi.first.wpilibj.SpeedController

        setVoltage
    • Field Detail

      • speedController

        protected final edu.wpi.first.wpilibj.SpeedController speedController
      • maxRotationalRate

        protected float maxRotationalRate
      • target

        protected float target
      • maxIntegralError

        protected final float maxIntegralError
      • deadband

        protected final float deadband
      • inverted

        protected boolean inverted
    • Constructor Detail

      • VelocityController

        public VelocityController​(edu.wpi.first.wpilibj.SpeedController speedController,
                                  edu.wpi.first.wpilibj.pidwrappers.PIDEncoder encoder,
                                  float maxRotationalRate,
                                  float kP,
                                  float kI,
                                  float kD,
                                  float maxIntegralError,
                                  float deadband)
        Construct a new VelocityController instance.
        Parameters:
        speedController - a backing SpeedController (ex physical Jaguar, Talon, Victor).
        encoder - an Encoder which measures the output of the associated physical SpeedController.
        maxRotationalRate - the maximum rotational rate as reported by the Encoder.
        kP - the Proportional PID constant.
        kI - the Integral PID constant.
        kD - the Derivative PID constant.
        maxIntegralError - limit constant for the integral error.
        deadband - if the absolute value of the deadband falls within this range, output 0.
      • VelocityController

        public VelocityController​(edu.wpi.first.wpilibj.SpeedController speedController,
                                  PIDRateValueSrc<edu.wpi.first.wpilibj.pidwrappers.PIDEncoder> encoderPidSrc,
                                  float maxRotationalRate,
                                  float kP,
                                  float kI,
                                  float kD,
                                  float maxIntegralError,
                                  float deadband)
        Construct a new VelocityController instance.
        Parameters:
        speedController - a backing SpeedController (ex physical Jaguar, Talon, Victor).
        encoderPidSrc - an EncoderPidSrc which measures the output of the associated physical SpeedController.
        maxRotationalRate - the maximum rotational rate as reported by the Encoder.
        kP - the Proportional PID constant.
        kI - the Integral PID constant.
        kD - the Derivative PID constant.
        maxIntegralError - limit constant for the integral error.
        deadband - if the absolute value of the deadband falls within this range, output 0.
    • Method Detail

      • get

        public double get()
        Get the target rotational rate proportion which this VelocityController is set to.
        Specified by:
        get in interface edu.wpi.first.wpilibj.SpeedController
        Returns:
        the proportional rotational rate target.
      • getRate

        public java.lang.Float getRate()
        Get the rate measured by this sensor.
        Specified by:
        getRate in interface PIDRateValueSrc<edu.wpi.first.wpilibj.pidwrappers.PIDEncoder>
        Returns:
        the rate value.
      • set

        public void set​(double v)
        Set the target rotational rate of this VelocityController. This method should be called very frequently, as the PID loop only iterates when this method is called.
        Specified by:
        set in interface edu.wpi.first.wpilibj.SpeedController
        Parameters:
        v - target value.
      • disable

        public void disable()
        Disable this VelocityController.
        Specified by:
        disable in interface edu.wpi.first.wpilibj.SpeedController
      • getComposedComponents

        public java.util.Collection<java.lang.Object> getComposedComponents()
        Get the composed components within this one.
        Specified by:
        getComposedComponents in interface ComposedComponent<java.lang.Object>
        Returns:
        the composed components.
      • pid

        public java.lang.Float pid​(java.lang.Float target)
        Iterate the PID loop.
        Specified by:
        pid in interface PID<edu.wpi.first.wpilibj.pidwrappers.PIDEncoder,​java.lang.Float>
        Specified by:
        pid in class AbstractPID<edu.wpi.first.wpilibj.pidwrappers.PIDEncoder,​java.lang.Float>
        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
      • getSensor

        public edu.wpi.first.wpilibj.pidwrappers.PIDEncoder getSensor()
        Get the sensor behind this PIDSrc.
        Specified by:
        getSensor in interface PIDSrc<edu.wpi.first.wpilibj.pidwrappers.PIDEncoder,​java.lang.Float>
        Returns:
        the sensor.
      • getPIDValue

        public java.lang.Float getPIDValue()
        Get the measured value of the sensor behind this PIDSrc.
        Specified by:
        getPIDValue in interface PIDSrc<edu.wpi.first.wpilibj.pidwrappers.PIDEncoder,​java.lang.Float>
        Returns:
        the value.
      • setPIDSourceType

        public void setPIDSourceType​(edu.wpi.first.wpilibj.PIDSourceType pidSourceType)
        Specified by:
        setPIDSourceType in interface edu.wpi.first.wpilibj.PIDSource
      • getPIDSourceType

        public edu.wpi.first.wpilibj.PIDSourceType getPIDSourceType()
        Specified by:
        getPIDSourceType in interface edu.wpi.first.wpilibj.PIDSource
      • setInverted

        public void setInverted​(boolean inverted)
        Specified by:
        setInverted in interface edu.wpi.first.wpilibj.SpeedController
      • getInverted

        public boolean getInverted()
        Specified by:
        getInverted in interface edu.wpi.first.wpilibj.SpeedController
      • stopMotor

        public void stopMotor()
        Specified by:
        stopMotor in interface edu.wpi.first.wpilibj.SpeedController