RobotCore
Robot Core Documentation
|
Public Member Functions | |
ParallelCommandGroup (Command... commands) | |
final void | addCommands (Command... commands) |
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< Subsystem > | getRequirements () |
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 | |
Static Public Member Functions inherited from edu.wpi.first.wpilibj2.command.CommandGroupBase | |
static void | clearGroupedCommands () |
static void | clearGroupedCommand (Command command) |
static void | requireUngrouped (Command... commands) |
static void | requireUngrouped (Collection< Command > commands) |
static CommandGroupBase | sequence (Command... commands) |
static CommandGroupBase | parallel (Command... commands) |
static CommandGroupBase | race (Command... commands) |
static CommandGroupBase | deadline (Command deadline, Command... commands) |
Protected Attributes inherited from edu.wpi.first.wpilibj2.command.CommandBase | |
Set< Subsystem > | m_requirements = new HashSet<>() |
A CommandGroup that runs a set of commands in parallel, ending when the last command ends.
As a rule, CommandGroups require the union of the requirements of their component commands.
edu.wpi.first.wpilibj2.command.ParallelCommandGroup.ParallelCommandGroup | ( | Command... | commands | ) |
Creates a new ParallelCommandGroup. The given commands will be executed simultaneously. The command group will finish when the last command finishes. If the CommandGroup is interrupted, only the commands that are still running will be interrupted.
commands | the commands to include in this group. |
final void edu.wpi.first.wpilibj2.command.ParallelCommandGroup.addCommands | ( | Command... | commands | ) |
Adds the given commands to the command group.
commands | The commands to add. |
Reimplemented from edu.wpi.first.wpilibj2.command.CommandGroupBase.
void edu.wpi.first.wpilibj2.command.ParallelCommandGroup.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 |
Implements edu.wpi.first.wpilibj2.command.Command.
void edu.wpi.first.wpilibj2.command.ParallelCommandGroup.execute | ( | ) |
The main body of a command. Called repeatedly while the command is scheduled.
Implements edu.wpi.first.wpilibj2.command.Command.
void edu.wpi.first.wpilibj2.command.ParallelCommandGroup.initialize | ( | ) |
The initial subroutine of a command. Called once when the command is initially scheduled.
Implements edu.wpi.first.wpilibj2.command.Command.
boolean edu.wpi.first.wpilibj2.command.ParallelCommandGroup.isFinished | ( | ) |
Whether the command has finished. Once a command finishes, the scheduler will call its end() method and un-schedule it.
Implements edu.wpi.first.wpilibj2.command.Command.
boolean edu.wpi.first.wpilibj2.command.ParallelCommandGroup.runsWhenDisabled | ( | ) |
Whether the given command should run when the robot is disabled. Override to return true if the command should run when disabled.
Implements edu.wpi.first.wpilibj2.command.Command.