Package edu.wpi.first.wpilibj.command
Class Subsystem
- java.lang.Object
-
- edu.wpi.first.wpilibj.command.Subsystem
-
- All Implemented Interfaces:
Sendable
,AutoCloseable
- Direct Known Subclasses:
PIDSubsystem
public abstract class Subsystem extends Object implements Sendable, AutoCloseable
This class defines a major component of the robot.A good example of a subsystem is the driveline, or a claw if the robot has one.
All motors should be a part of a subsystem. For instance, all the wheel motors should be a part of some kind of "Driveline" subsystem.
Subsystems are used within the command system as requirements for
Command
. Only one command which requires a subsystem can run at a time. Also, subsystems can have default commands which are started if there is no command running which requires this subsystem.- See Also:
Command
-
-
Method Summary
All Methods Instance Methods Abstract Methods Concrete Methods Modifier and Type Method Description void
addChild(Sendable child)
Associate aSendable
with this Subsystem.void
addChild(String name, Sendable child)
Associate aSendable
with this Subsystem.void
close()
Command
getCurrentCommand()
Returns the command which currently claims this subsystem.String
getCurrentCommandName()
Returns the current command name, or empty string if no current command.Command
getDefaultCommand()
Returns the default command (or null if there is none).String
getDefaultCommandName()
Returns the default command name, or empty string is there is none.String
getName()
Gets the name of this Subsystem.String
getSubsystem()
Gets the subsystem name of this Subsystem.protected abstract void
initDefaultCommand()
Initialize the default command for a subsystem By default subsystems have no default command, but if they do, the default command is set with this method.void
initSendable(SendableBuilder builder)
Initializes thisSendable
object.void
periodic()
When the run method of the scheduler is called this method will be called.void
setDefaultCommand(Command command)
Sets the default command.void
setName(String name)
Sets the name of this Subsystem.void
setSubsystem(String subsystem)
Sets the subsystem name of this Subsystem.String
toString()
-
-
-
Method Detail
-
close
public void close()
- Specified by:
close
in interfaceAutoCloseable
-
initDefaultCommand
protected abstract void initDefaultCommand()
Initialize the default command for a subsystem By default subsystems have no default command, but if they do, the default command is set with this method. It is called on all Subsystems by CommandBase in the users program after all the Subsystems are created.
-
periodic
public void periodic()
When the run method of the scheduler is called this method will be called.
-
setDefaultCommand
public void setDefaultCommand(Command command)
Sets the default command. If this is not called or is called with null, then there will be no default command for the subsystem.WARNING: This should NOT be called in a constructor if the subsystem is a singleton.
- Parameters:
command
- the default command (or null if there should be none)- Throws:
IllegalUseOfCommandException
- if the command does not require the subsystem
-
getDefaultCommand
public Command getDefaultCommand()
Returns the default command (or null if there is none).- Returns:
- the default command
-
getDefaultCommandName
public String getDefaultCommandName()
Returns the default command name, or empty string is there is none.- Returns:
- the default command name
-
getCurrentCommand
public Command getCurrentCommand()
Returns the command which currently claims this subsystem.- Returns:
- the command which currently claims this subsystem
-
getCurrentCommandName
public String getCurrentCommandName()
Returns the current command name, or empty string if no current command.- Returns:
- the current command name
-
addChild
public void addChild(String name, Sendable child)
Associate aSendable
with this Subsystem. Also update the child's name.- Parameters:
name
- name to give childchild
- sendable
-
addChild
public void addChild(Sendable child)
Associate aSendable
with this Subsystem.- Parameters:
child
- sendable
-
getSubsystem
public String getSubsystem()
Gets the subsystem name of this Subsystem.- Returns:
- Subsystem name
-
setSubsystem
public void setSubsystem(String subsystem)
Sets the subsystem name of this Subsystem.- Parameters:
subsystem
- subsystem name
-
initSendable
public void initSendable(SendableBuilder builder)
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Parameters:
builder
- sendable builder
-
-