|
Robot Core Documentation
|
Public Member Functions | |
| FunctionalCommand (Runnable onInit, Runnable onExecute, Consumer< Boolean > onEnd, BooleanSupplier isFinished, Subsystem... requirements) | |
| void | initialize () |
| void | execute () |
| void | end (boolean interrupted) |
| boolean | isFinished () |
Public Member Functions inherited from edu.wpi.first.wpilibj2.command.Command | |
| Set< Subsystem > | getRequirements () |
| final void | addRequirements (Subsystem... requirements) |
| String | getName () |
| void | setName (String name) |
| String | getSubsystem () |
| void | setSubsystem (String subsystem) |
| ParallelRaceGroup | withTimeout (double seconds) |
| ParallelRaceGroup | until (BooleanSupplier condition) |
| ParallelRaceGroup | onlyWhile (BooleanSupplier condition) |
| SequentialCommandGroup | beforeStarting (Runnable toRun, Subsystem... requirements) |
| SequentialCommandGroup | beforeStarting (Command before) |
| SequentialCommandGroup | andThen (Runnable toRun, Subsystem... requirements) |
| SequentialCommandGroup | andThen (Command... next) |
| ParallelDeadlineGroup | deadlineWith (Command... parallel) |
| ParallelCommandGroup | alongWith (Command... parallel) |
| ParallelRaceGroup | raceWith (Command... parallel) |
| RepeatCommand | repeatedly () |
| ProxyCommand | asProxy () |
| ConditionalCommand | unless (BooleanSupplier condition) |
| ConditionalCommand | onlyIf (BooleanSupplier condition) |
| WrapperCommand | ignoringDisable (boolean doesRunWhenDisabled) |
| WrapperCommand | withInterruptBehavior (InterruptionBehavior interruptBehavior) |
| WrapperCommand | finallyDo (BooleanConsumer end) |
| WrapperCommand | finallyDo (Runnable end) |
| WrapperCommand | handleInterrupt (Runnable handler) |
| void | schedule () |
| void | cancel () |
| boolean | isScheduled () |
| boolean | hasRequirement (Subsystem requirement) |
| InterruptionBehavior | getInterruptionBehavior () |
| boolean | runsWhenDisabled () |
| WrapperCommand | withName (String name) |
| void | initSendable (SendableBuilder builder) |
Public Member Functions inherited from edu.wpi.first.util.sendable.Sendable | |
Additional Inherited Members | |
Protected Member Functions inherited from edu.wpi.first.wpilibj2.command.Command | |
| Command () | |
Protected Attributes inherited from edu.wpi.first.wpilibj2.command.Command | |
| Set< Subsystem > | m_requirements = new HashSet<>() |
A command that allows the user to pass in functions for each of the basic command methods through the constructor. Useful for inline definitions of complex commands - note, however, that if a command is beyond a certain complexity it is usually better practice to write a proper class for it than to inline it.
This class is provided by the NewCommands VendorDep
| edu.wpi.first.wpilibj2.command.FunctionalCommand.FunctionalCommand | ( | Runnable | onInit, |
| Runnable | onExecute, | ||
| Consumer< Boolean > | onEnd, | ||
| BooleanSupplier | isFinished, | ||
| Subsystem... | requirements ) |
Creates a new FunctionalCommand.
| onInit | the function to run on command initialization |
| onExecute | the function to run on command execution |
| onEnd | the function to run on command end |
| isFinished | the function that determines whether the command has finished |
| requirements | the subsystems required by this command |
| void edu.wpi.first.wpilibj2.command.FunctionalCommand.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.FunctionalCommand.execute | ( | ) |
The main body of a command. Called repeatedly while the command is scheduled.
Reimplemented from edu.wpi.first.wpilibj2.command.Command.
| void edu.wpi.first.wpilibj2.command.FunctionalCommand.initialize | ( | ) |
The initial subroutine of a command. Called once when the command is initially scheduled.
Reimplemented from edu.wpi.first.wpilibj2.command.Command.
| boolean edu.wpi.first.wpilibj2.command.FunctionalCommand.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.