Class ProfiledPIDSubsystem

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

public abstract class ProfiledPIDSubsystem
extends SubsystemBase
A subsystem that uses a ProfiledPIDController 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

  • 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

      Returns the ProfiledPIDController.
      Returns:
      The controller.
    • setGoal

      public final void setGoal​(TrapezoidProfile.State goal)
      Sets the goal state for the subsystem.
      Parameters:
      goal - The goal state for the subsystem's motion profile.
    • setGoal

      public final void setGoal​(double goal)
      Sets the goal state for the subsystem. Goal velocity assumed to be zero.
      Parameters:
      goal - The goal position for the subsystem's motion profile.
    • useOutput

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

      protected abstract double getMeasurement()
      Returns the measurement of the process variable used by the ProfiledPIDController.
      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.