RobotCore
Robot Core Documentation
|
Public Member Functions | |
ScheduleCommand (Command... toSchedule) | |
void | initialize () |
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 void | execute () |
default void | end (boolean interrupted) |
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 | |
Protected Attributes inherited from edu.wpi.first.wpilibj2.command.CommandBase | |
Set< Subsystem > | m_requirements = new HashSet<>() |
Schedules the given commands when this command is initialized. Useful for forking off from CommandGroups. Note that if run from a CommandGroup, the group will not know about the status of the scheduled commands, and will treat this command as finishing instantly.
edu.wpi.first.wpilibj2.command.ScheduleCommand.ScheduleCommand | ( | Command... | toSchedule | ) |
Creates a new ScheduleCommand that schedules the given commands when initialized.
toSchedule | the commands to schedule |
void edu.wpi.first.wpilibj2.command.ScheduleCommand.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.ScheduleCommand.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.ScheduleCommand.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.