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

Public Member Functions

 WaitCommand (double seconds)
 
void initialize ()
 
void end (boolean interrupted)
 
boolean isFinished ()
 
boolean runsWhenDisabled ()
 
void initSendable (SendableBuilder builder)
 
- Public Member Functions inherited from edu.wpi.first.wpilibj2.command.Command
void execute ()
 
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

Protected Attributes

Timer m_timer = new Timer()
 
- Protected Attributes inherited from edu.wpi.first.wpilibj2.command.Command
Set< Subsystemm_requirements = new HashSet<>()
 

Additional Inherited Members

- Protected Member Functions inherited from edu.wpi.first.wpilibj2.command.Command
 Command ()
 

Detailed Description

A command that does nothing but takes a specified amount of time to finish.

This class is provided by the NewCommands VendorDep

Constructor & Destructor Documentation

◆ WaitCommand()

edu.wpi.first.wpilibj2.command.WaitCommand.WaitCommand ( double seconds)

Creates a new WaitCommand. This command will do nothing, and end after the specified duration.

Parameters
secondsthe time to wait, in seconds

Member Function Documentation

◆ end()

void edu.wpi.first.wpilibj2.command.WaitCommand.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.

◆ initialize()

void edu.wpi.first.wpilibj2.command.WaitCommand.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.WaitCommand.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.WaitCommand.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.WaitCommand.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.

Member Data Documentation

◆ m_timer

Timer edu.wpi.first.wpilibj2.command.WaitCommand.m_timer = new Timer()
protected

The timer used for waiting.


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