Package edu.wpi.first.wpilibj2.command
Interface Subsystem
-
- All Known Implementing Classes:
PIDSubsystem
,ProfiledPIDSubsystem
,SubsystemBase
,TrapezoidProfileSubsystem
public interface Subsystem
A robot subsystem. Subsystems are the basic unit of robot organization in the Command-based framework; they encapsulate low-level hardware objects (motor controllers, sensors, etc) and provide methods through which they can be used byCommand
s. Subsystems are used by theCommandScheduler
's resource management system to ensure multiple robot actions are not "fighting" over the same hardware; Commands that use a subsystem should include that subsystem in theirCommand.getRequirements()
method, and resources used within a subsystem should generally remain encapsulated and not be shared by other parts of the robot.Subsystems must be registered with the scheduler with the
CommandScheduler.registerSubsystem(Subsystem...)
method in order for theperiodic()
method to be called. It is recommended that this method be called from the constructor of users' Subsystem implementations. TheSubsystemBase
class offers a simple base for user implementations that handles this.
-
-
Method Summary
All Methods Instance Methods Default Methods Modifier and Type Method Description default Command
getCurrentCommand()
Returns the command currently running on this subsystem.default Command
getDefaultCommand()
Gets the default command for this subsystem.default void
periodic()
This method is called periodically by theCommandScheduler
.default void
register()
Registers this subsystem with theCommandScheduler
, allowing itsperiodic()
method to be called when the scheduler runs.default void
setDefaultCommand(Command defaultCommand)
Sets the defaultCommand
of the subsystem.default void
simulationPeriodic()
This method is called periodically by theCommandScheduler
.
-
-
-
Method Detail
-
periodic
default void periodic()
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.
-
simulationPeriodic
default void simulationPeriodic()
This method is called periodically by theCommandScheduler
. Useful for updating subsystem-specific state that needs to be maintained for simulations, such as for updatingedu.wpi.first.wpilibj.simulation
classes and setting simulated sensor readings.
-
setDefaultCommand
default void setDefaultCommand(Command defaultCommand)
Sets the defaultCommand
of the subsystem. The default command will be automatically scheduled when no other commands are scheduled that require the subsystem. Default commands should generally not end on their own, i.e. theirCommand.isFinished()
method should always return false. Will automatically register this subsystem with theCommandScheduler
.- Parameters:
defaultCommand
- the default command to associate with this subsystem
-
getDefaultCommand
default Command getDefaultCommand()
Gets the default command for this subsystem. Returns null if no default command is currently associated with the subsystem.- Returns:
- the default command associated with this subsystem
-
getCurrentCommand
default Command getCurrentCommand()
Returns the command currently running on this subsystem. Returns null if no command is currently scheduled that requires this subsystem.- Returns:
- the scheduled command currently requiring this subsystem
-
register
default void register()
Registers this subsystem with theCommandScheduler
, allowing itsperiodic()
method to be called when the scheduler runs.
-
-