Class PIDSubsystem

  • All Implemented Interfaces:
    Sendable, AutoCloseable

    public abstract class PIDSubsystem
    extends Subsystem
    This class is designed to handle the case where there is a Subsystem which uses a single PIDController almost constantly (for instance, an elevator which attempts to stay at a constant height).

    It provides some convenience methods to run an internal PIDController . It also allows access to the internal PIDController in order to give total control to the programmer.

    • Constructor Detail

      • PIDSubsystem

        public PIDSubsystem​(String name,
                            double p,
                            double i,
                            double d)
        Instantiates a PIDSubsystem that will use the given p, i and d values.
        Parameters:
        name - the name
        p - the proportional value
        i - the integral value
        d - the derivative value
      • PIDSubsystem

        public PIDSubsystem​(String name,
                            double p,
                            double i,
                            double d,
                            double f)
        Instantiates a PIDSubsystem that will use the given p, i and d values.
        Parameters:
        name - the name
        p - the proportional value
        i - the integral value
        d - the derivative value
        f - the feed forward value
      • PIDSubsystem

        public PIDSubsystem​(String name,
                            double p,
                            double i,
                            double d,
                            double f,
                            double period)
        Instantiates a PIDSubsystem that will use the given p, i and d values. It will also space the time between PID loop calculations to be equal to the given period.
        Parameters:
        name - the name
        p - the proportional value
        i - the integral value
        d - the derivative value
        f - the feed forward value
        period - the time (in seconds) between calculations
      • PIDSubsystem

        public PIDSubsystem​(double p,
                            double i,
                            double d)
        Instantiates a PIDSubsystem that will use the given p, i and d values. It will use the class name as its name.
        Parameters:
        p - the proportional value
        i - the integral value
        d - the derivative value
      • PIDSubsystem

        public PIDSubsystem​(double p,
                            double i,
                            double d,
                            double f,
                            double period)
        Instantiates a PIDSubsystem that will use the given p, i and d values. It will use the class name as its name. It will also space the time between PID loop calculations to be equal to the given period.
        Parameters:
        p - the proportional value
        i - the integral value
        d - the derivative value
        f - the feed forward coefficient
        period - the time (in seconds) between calculations
      • PIDSubsystem

        public PIDSubsystem​(double p,
                            double i,
                            double d,
                            double period)
        Instantiates a PIDSubsystem that will use the given p, i and d values. It will use the class name as its name. It will also space the time between PID loop calculations to be equal to the given period.
        Parameters:
        p - the proportional value
        i - the integral value
        d - the derivative value
        period - the time (in seconds) between calculations
    • Method Detail

      • setSetpointRelative

        public void setSetpointRelative​(double deltaSetpoint)
        Adds the given value to the setpoint. If setInputRange(...) was used, then the bounds will still be honored by this method.
        Parameters:
        deltaSetpoint - the change in the setpoint
      • setSetpoint

        public void setSetpoint​(double setpoint)
        Sets the setpoint to the given value. If setInputRange(...) was called, then the given setpoint will be trimmed to fit within the range.
        Parameters:
        setpoint - the new setpoint
      • getSetpoint

        public double getSetpoint()
        Returns the setpoint.
        Returns:
        the setpoint
      • getPosition

        public double getPosition()
        Returns the current position.
        Returns:
        the current position
      • setInputRange

        public void setInputRange​(double minimumInput,
                                  double maximumInput)
        Sets the maximum and minimum values expected from the input.
        Parameters:
        minimumInput - the minimum value expected from the input
        maximumInput - the maximum value expected from the output
      • setOutputRange

        public void setOutputRange​(double minimumOutput,
                                   double maximumOutput)
        Sets the maximum and minimum values to write.
        Parameters:
        minimumOutput - the minimum value to write to the output
        maximumOutput - the maximum value to write to the output
      • setAbsoluteTolerance

        public void setAbsoluteTolerance​(double t)
        Set the absolute error which is considered tolerable for use with OnTarget. The value is in the same range as the PIDInput values.
        Parameters:
        t - the absolute tolerance
      • setPercentTolerance

        public void setPercentTolerance​(double p)
        Set the percentage error which is considered tolerable for use with OnTarget. (Value of 15.0 == 15 percent).
        Parameters:
        p - the percent tolerance
      • onTarget

        public boolean onTarget()
        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
      • returnPIDInput

        protected abstract double returnPIDInput()
        Returns the input for the pid loop.

        It returns the input for the pid loop, so if this Subsystem was based off of a gyro, then it should return the angle of the gyro.

        All subclasses of PIDSubsystem must override this method.

        Returns:
        the value the pid loop should use as input
      • usePIDOutput

        protected abstract void usePIDOutput​(double output)
        Uses the value that the pid loop calculated. The calculated value is the "output" parameter. This method is a good time to set motor values, maybe something along the lines of driveline.tankDrive(output, -output).

        All subclasses of PIDSubsystem must override this method.

        Parameters:
        output - the value the pid loop calculated
      • enable

        public void enable()
        Enables the internal PIDController.
      • disable

        public void disable()
        Disables the internal PIDController.