Class PIDSubsystem

java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
edu.wpi.first.wpilibj2.command.PIDSubsystem
All Implemented Interfaces:
Sendable, Subsystem

public abstract class PIDSubsystem
extends SubsystemBase
A subsystem that uses a PIDController to control an output. The controller is run synchronously from the subsystem's periodic() method.

This class is provided by the NewCommands VendorDep

  • Field Details

  • Constructor Details

    • PIDSubsystem

      public PIDSubsystem​(PIDController controller, double initialPosition)
      Creates a new PIDSubsystem.
      Parameters:
      controller - the PIDController to use
      initialPosition - the initial setpoint of the subsystem
    • PIDSubsystem

      public PIDSubsystem​(PIDController controller)
      Creates a new PIDSubsystem. Initial setpoint is zero.
      Parameters:
      controller - the PIDController to use
  • Method Details

    • periodic

      public void periodic()
      Description copied from interface: Subsystem
      This method is called periodically by the CommandScheduler. Useful for updating subsystem-specific state that you don't want to offload to a Command. Teams should try to be consistent within their own codebases about which responsibilities will be handled by Commands, and which will be handled here.
    • getController

    • setSetpoint

      public void setSetpoint​(double setpoint)
      Sets the setpoint for the subsystem.
      Parameters:
      setpoint - the setpoint for the subsystem
    • getSetpoint

      public double getSetpoint()
      Returns the current setpoint of the subsystem.
      Returns:
      The current setpoint
    • useOutput

      protected abstract void useOutput​(double output, double setpoint)
      Uses the output from the PIDController.
      Parameters:
      output - the output of the PIDController
      setpoint - the setpoint of the PIDController (for feedforward)
    • getMeasurement

      protected abstract double getMeasurement()
      Returns the measurement of the process variable used by the PIDController.
      Returns:
      the measurement of the process variable
    • enable

      public void enable()
      Enables the PID control. Resets the controller.
    • disable

      public void disable()
      Disables the PID control. Sets output to zero.
    • isEnabled

      public boolean isEnabled()
      Returns whether the controller is enabled.
      Returns:
      Whether the controller is enabled.