Class TrapezoidProfileSubsystem

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

public abstract class TrapezoidProfileSubsystem
extends SubsystemBase
A subsystem that generates and runs trapezoidal motion profiles automatically. The user specifies how to use the current state of the motion profile by overriding the `useState` method.
  • 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.
    • setGoal

      public 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 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.
    • enable

      public void enable()
      Enable the TrapezoidProfileSubsystem's output.
    • disable

      public void disable()
      Disable the TrapezoidProfileSubsystem's output.
    • useState

      protected abstract void useState​(TrapezoidProfile.State state)
      Users should override this to consume the current state of the motion profile.
      Parameters:
      state - The current state of the motion profile.