Robot Core Documentation
Loading...
Searching...
No Matches
edu.wpi.first.wpilibj2.command.ParallelCommandGroup Class Reference
Inheritance diagram for edu.wpi.first.wpilibj2.command.ParallelCommandGroup:
edu.wpi.first.wpilibj2.command.Command edu.wpi.first.util.sendable.Sendable

Public Member Functions

 ParallelCommandGroup (Command... commands)
 
final void addCommands (Command... commands)
 
final void initialize ()
 
final void execute ()
 
final void end (boolean interrupted)
 
final boolean isFinished ()
 
boolean runsWhenDisabled ()
 
InterruptionBehavior getInterruptionBehavior ()
 
- Public Member Functions inherited from edu.wpi.first.wpilibj2.command.Command
Set< SubsystemgetRequirements ()
 
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)
 
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< Subsystemm_requirements = new HashSet<>()
 

Detailed Description

A command composition that runs a set of commands in parallel, ending when the last command ends.

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

Constructor & Destructor Documentation

◆ ParallelCommandGroup()

edu.wpi.first.wpilibj2.command.ParallelCommandGroup.ParallelCommandGroup ( Command... commands)

Creates a new ParallelCommandGroup. The given commands will be executed simultaneously. The command composition will finish when the last command finishes. If the composition is interrupted, only the commands that are still running will be interrupted.

Parameters
commandsthe commands to include in this composition.

Member Function Documentation

◆ addCommands()

final void edu.wpi.first.wpilibj2.command.ParallelCommandGroup.addCommands ( Command... commands)

Adds the given commands to the group.

Parameters
commandsCommands to add to the group.

◆ end()

final 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.

Parameters
interruptedwhether the command was interrupted/canceled

Reimplemented from edu.wpi.first.wpilibj2.command.Command.

◆ execute()

final void edu.wpi.first.wpilibj2.command.ParallelCommandGroup.execute ( )

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

Reimplemented from edu.wpi.first.wpilibj2.command.Command.

◆ getInterruptionBehavior()

InterruptionBehavior edu.wpi.first.wpilibj2.command.ParallelCommandGroup.getInterruptionBehavior ( )

How the command behaves when another command with a shared requirement is scheduled.

Returns
a variant of InterruptionBehavior, defaulting to kCancelSelf.

Reimplemented from edu.wpi.first.wpilibj2.command.Command.

◆ initialize()

final void edu.wpi.first.wpilibj2.command.ParallelCommandGroup.initialize ( )

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

Reimplemented from edu.wpi.first.wpilibj2.command.Command.

◆ isFinished()

final 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.

Returns
whether the command has finished.

Reimplemented from edu.wpi.first.wpilibj2.command.Command.

◆ runsWhenDisabled()

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.

Returns
whether the command should run when the robot is disabled

Reimplemented from edu.wpi.first.wpilibj2.command.Command.


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