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

Public Member Functions

 ProxyCommand (Supplier< Command > supplier)
 
 ProxyCommand (Command command)
 
void initialize ()
 
void end (boolean interrupted)
 
void execute ()
 
boolean isFinished ()
 
boolean runsWhenDisabled ()
 
void initSendable (SendableBuilder builder)
 
- 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)
 
InterruptionBehavior getInterruptionBehavior ()
 
WrapperCommand withName (String name)
 
- 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

Schedules the given command when this command is initialized, and ends when it ends. Useful for forking off from CommandGroups. If this command is interrupted, it will cancel the command.

This class is provided by the NewCommands VendorDep

Constructor & Destructor Documentation

◆ ProxyCommand() [1/2]

edu.wpi.first.wpilibj2.command.ProxyCommand.ProxyCommand ( Supplier< Command > supplier)

Creates a new ProxyCommand that schedules the supplied command when initialized, and ends when it is no longer scheduled. Useful for lazily creating commands at runtime.

Parameters
supplierthe command supplier

◆ ProxyCommand() [2/2]

edu.wpi.first.wpilibj2.command.ProxyCommand.ProxyCommand ( Command command)

Creates a new ProxyCommand that schedules the given command when initialized, and ends when it is no longer scheduled.

Parameters
commandthe command to run by proxy

Member Function Documentation

◆ end()

void edu.wpi.first.wpilibj2.command.ProxyCommand.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()

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

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

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

◆ initialize()

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

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

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

◆ initSendable()

void edu.wpi.first.wpilibj2.command.ProxyCommand.initSendable ( SendableBuilder builder)

Initializes this Sendable object.

Parameters
buildersendable builder

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

◆ isFinished()

boolean edu.wpi.first.wpilibj2.command.ProxyCommand.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.ProxyCommand.runsWhenDisabled ( )

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

Returns
true. Otherwise, this proxy would cancel commands that do run when disabled.

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


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