Robot Core Documentation
Loading...
Searching...
No Matches
edu.wpi.first.wpilibj2.command.FunctionalCommand Class Reference
Inheritance diagram for edu.wpi.first.wpilibj2.command.FunctionalCommand:
edu.wpi.first.wpilibj2.command.Command edu.wpi.first.util.sendable.Sendable edu.wpi.first.wpilibj2.command.InstantCommand edu.wpi.first.wpilibj2.command.RunCommand edu.wpi.first.wpilibj2.command.StartEndCommand edu.wpi.first.wpilibj2.command.PrintCommand

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< 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 ()
 
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< Subsystemm_requirements = new HashSet<>()
 

Detailed Description

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

Constructor & Destructor Documentation

◆ FunctionalCommand()

edu.wpi.first.wpilibj2.command.FunctionalCommand.FunctionalCommand ( Runnable onInit,
Runnable onExecute,
Consumer< Boolean > onEnd,
BooleanSupplier isFinished,
Subsystem... requirements )

Creates a new FunctionalCommand.

Parameters
onInitthe function to run on command initialization
onExecutethe function to run on command execution
onEndthe function to run on command end
isFinishedthe function that determines whether the command has finished
requirementsthe subsystems required by this command

Member Function Documentation

◆ end()

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.

Parameters
interruptedwhether the command was interrupted/canceled

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

◆ execute()

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.

◆ initialize()

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.

◆ isFinished()

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.

Returns
whether the command has finished.

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


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