Package edu.wpi.first.wpilibj2.command
Class TrapezoidProfileSubsystem
- java.lang.Object
-
- edu.wpi.first.wpilibj2.command.SubsystemBase
-
- edu.wpi.first.wpilibj2.command.TrapezoidProfileSubsystem
-
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 Summary
Constructors Constructor Description TrapezoidProfileSubsystem(TrapezoidProfile.Constraints constraints)
Creates a new TrapezoidProfileSubsystem.TrapezoidProfileSubsystem(TrapezoidProfile.Constraints constraints, double initialPosition)
Creates a new TrapezoidProfileSubsystem.TrapezoidProfileSubsystem(TrapezoidProfile.Constraints constraints, double initialPosition, double period)
Creates a new TrapezoidProfileSubsystem.
-
Method Summary
All Methods Instance Methods Abstract Methods Concrete Methods Modifier and Type Method Description void
disable()
Disable the TrapezoidProfileSubsystem's output.void
enable()
Enable the TrapezoidProfileSubsystem's output.void
periodic()
This method is called periodically by theCommandScheduler
.void
setGoal(double goal)
Sets the goal state for the subsystem.void
setGoal(TrapezoidProfile.State goal)
Sets the goal state for the subsystem.protected abstract void
useState(TrapezoidProfile.State state)
Users should override this to consume the current state of the motion profile.-
Methods inherited from class edu.wpi.first.wpilibj2.command.SubsystemBase
addChild, getName, getSubsystem, initSendable, setName, setSubsystem
-
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
-
Methods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem
getCurrentCommand, getDefaultCommand, register, setDefaultCommand, simulationPeriodic
-
-
-
-
Constructor Detail
-
TrapezoidProfileSubsystem
public TrapezoidProfileSubsystem(TrapezoidProfile.Constraints constraints, double initialPosition, double period)
Creates a new TrapezoidProfileSubsystem.- Parameters:
constraints
- The constraints (maximum velocity and acceleration) for the profiles.initialPosition
- The initial position of the controlled mechanism when the subsystem is constructed.period
- The period of the main robot loop, in seconds.
-
TrapezoidProfileSubsystem
public TrapezoidProfileSubsystem(TrapezoidProfile.Constraints constraints, double initialPosition)
Creates a new TrapezoidProfileSubsystem.- Parameters:
constraints
- The constraints (maximum velocity and acceleration) for the profiles.initialPosition
- The initial position of the controlled mechanism when the subsystem is constructed.
-
TrapezoidProfileSubsystem
public TrapezoidProfileSubsystem(TrapezoidProfile.Constraints constraints)
Creates a new TrapezoidProfileSubsystem.- Parameters:
constraints
- The constraints (maximum velocity and acceleration) for the profiles.
-
-
Method Detail
-
periodic
public void periodic()
Description copied from interface:Subsystem
This method is called periodically by theCommandScheduler
. Useful for updating subsystem-specific state that you don't want to offload to aCommand
. 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.
-
-