RobotCore
Robot Core Documentation
Public Member Functions | List of all members
edu.wpi.first.wpilibj2.command.SelectCommand Class Reference
Inheritance diagram for edu.wpi.first.wpilibj2.command.SelectCommand:
edu.wpi.first.wpilibj2.command.CommandBase edu.wpi.first.wpilibj2.command.Command

Public Member Functions

 SelectCommand (Map< Object, Command > commands, Supplier< Object > selector)
 
 SelectCommand (Supplier< Command > toRun)
 
void initialize ()
 
void execute ()
 
void end (boolean interrupted)
 
boolean isFinished ()
 
boolean runsWhenDisabled ()
 
- Public Member Functions inherited from edu.wpi.first.wpilibj2.command.CommandBase
final void addRequirements (Subsystem... requirements)
 
Set< SubsystemgetRequirements ()
 
- Public Member Functions inherited from edu.wpi.first.wpilibj2.command.Command
default ParallelRaceGroup withTimeout (double seconds)
 
default ParallelRaceGroup withInterrupt (BooleanSupplier condition)
 
default SequentialCommandGroup beforeStarting (Runnable toRun, Subsystem... requirements)
 
default SequentialCommandGroup andThen (Runnable toRun, Subsystem... requirements)
 
default SequentialCommandGroup andThen (Command... next)
 
default ParallelDeadlineGroup deadlineWith (Command... parallel)
 
default ParallelCommandGroup alongWith (Command... parallel)
 
default ParallelRaceGroup raceWith (Command... parallel)
 
default PerpetualCommand perpetually ()
 
default ProxyScheduleCommand asProxy ()
 
default void schedule (boolean interruptible)
 
default void schedule ()
 
default void cancel ()
 
default boolean isScheduled ()
 
default boolean hasRequirement (Subsystem requirement)
 
default String getName ()
 

Additional Inherited Members

- Protected Attributes inherited from edu.wpi.first.wpilibj2.command.CommandBase
Set< Subsystemm_requirements = new HashSet<>()
 

Detailed Description

Runs one of a selection of commands, either using a selector and a key to command mapping, or a supplier that returns the command directly at runtime. Does not actually schedule the selected command - rather, the command is run through this command; this ensures that the command will behave as expected if used as part of a CommandGroup. Requires the requirements of all included commands, again to ensure proper functioning when used in a CommandGroup. If this is undesired, consider using ScheduleCommand.

As this command contains multiple component commands within it, it is technically a command group; the command instances that are passed to it cannot be added to any other groups, or scheduled individually.

As a rule, CommandGroups require the union of the requirements of their component commands.

Constructor & Destructor Documentation

◆ SelectCommand() [1/2]

edu.wpi.first.wpilibj2.command.SelectCommand.SelectCommand ( Map< Object, Command commands,
Supplier< Object >  selector 
)

Creates a new selectcommand.

Parameters
commandsthe map of commands to choose from
selectorthe selector to determine which command to run

◆ SelectCommand() [2/2]

edu.wpi.first.wpilibj2.command.SelectCommand.SelectCommand ( Supplier< Command toRun)

Creates a new selectcommand.

Parameters
toRuna supplier providing the command to run

Member Function Documentation

◆ end()

void edu.wpi.first.wpilibj2.command.SelectCommand.end ( boolean  interrupted)

The action to take when the command ends. Called when either the command finishes normally, or when it interrupted/canceled.

Do not schedule commands here that share requirements with this command. Use andThen(Command...) instead.

Parameters
interruptedwhether the command was interrupted/canceled

Implements edu.wpi.first.wpilibj2.command.Command.

◆ execute()

void edu.wpi.first.wpilibj2.command.SelectCommand.execute ( )

The main body of a command. Called repeatedly while the command is scheduled.

Implements edu.wpi.first.wpilibj2.command.Command.

◆ initialize()

void edu.wpi.first.wpilibj2.command.SelectCommand.initialize ( )

The initial subroutine of a command. Called once when the command is initially scheduled.

Implements edu.wpi.first.wpilibj2.command.Command.

◆ isFinished()

boolean edu.wpi.first.wpilibj2.command.SelectCommand.isFinished ( )

Whether the command has finished. Once a command finishes, the scheduler will call its end() method and un-schedule it.

Returns
whether the command has finished.

Implements edu.wpi.first.wpilibj2.command.Command.

◆ runsWhenDisabled()

boolean edu.wpi.first.wpilibj2.command.SelectCommand.runsWhenDisabled ( )

Whether the given command should run when the robot is disabled. Override to return true if the command should run when disabled.

Returns
whether the command should run when the robot is disabled

Implements edu.wpi.first.wpilibj2.command.Command.


The documentation for this class was generated from the following file: