Robot Core Documentation
|
Additional Inherited Members | |
![]() | |
Command () | |
![]() | |
Set< Subsystem > | m_requirements = new HashSet<>() |
A command composition that runs one of two commands, depending on the value of the given condition when this command is initialized.
The rules for command compositions apply: command instances that are passed to it cannot be added to any other composition or scheduled individually, and the composition requires all subsystems its components require.
This class is provided by the NewCommands VendorDep
edu.wpi.first.wpilibj2.command.ConditionalCommand.ConditionalCommand | ( | Command | onTrue, |
Command | onFalse, | ||
BooleanSupplier | condition ) |
Creates a new ConditionalCommand.
onTrue | the command to run if the condition is true |
onFalse | the command to run if the condition is false |
condition | the condition to determine which command to run |
void edu.wpi.first.wpilibj2.command.ConditionalCommand.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.
interrupted | whether the command was interrupted/canceled |
Reimplemented from edu.wpi.first.wpilibj2.command.Command.
void edu.wpi.first.wpilibj2.command.ConditionalCommand.execute | ( | ) |
The main body of a command. Called repeatedly while the command is scheduled.
Reimplemented from edu.wpi.first.wpilibj2.command.Command.
InterruptionBehavior edu.wpi.first.wpilibj2.command.ConditionalCommand.getInterruptionBehavior | ( | ) |
How the command behaves when another command with a shared requirement is scheduled.
InterruptionBehavior
, defaulting to kCancelSelf
. Reimplemented from edu.wpi.first.wpilibj2.command.Command.
void edu.wpi.first.wpilibj2.command.ConditionalCommand.initialize | ( | ) |
The initial subroutine of a command. Called once when the command is initially scheduled.
Reimplemented from edu.wpi.first.wpilibj2.command.Command.
void edu.wpi.first.wpilibj2.command.ConditionalCommand.initSendable | ( | SendableBuilder | builder | ) |
Initializes this Sendable
object.
builder | sendable builder |
Reimplemented from edu.wpi.first.wpilibj2.command.Command.
boolean edu.wpi.first.wpilibj2.command.ConditionalCommand.isFinished | ( | ) |
Whether the command has finished. Once a command finishes, the scheduler will call its end() method and un-schedule it.
Reimplemented from edu.wpi.first.wpilibj2.command.Command.
boolean edu.wpi.first.wpilibj2.command.ConditionalCommand.runsWhenDisabled | ( | ) |
Whether the given command should run when the robot is disabled. Override to return true if the command should run when disabled.
Reimplemented from edu.wpi.first.wpilibj2.command.Command.