Package edu.wpi.first.wpilibj2.command
Class ScheduleCommand
- java.lang.Object
-
- edu.wpi.first.wpilibj2.command.CommandBase
-
- edu.wpi.first.wpilibj2.command.ScheduleCommand
-
public class ScheduleCommand extends CommandBase
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.
-
-
Field Summary
-
Fields inherited from class edu.wpi.first.wpilibj2.command.CommandBase
m_requirements
-
-
Constructor Summary
Constructors Constructor Description ScheduleCommand(Command... toSchedule)
Creates a new ScheduleCommand that schedules the given commands when initialized.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description void
initialize()
The initial subroutine of a command.boolean
isFinished()
Whether the command has finished.boolean
runsWhenDisabled()
Whether the given command should run when the robot is disabled.-
Methods inherited from class edu.wpi.first.wpilibj2.command.CommandBase
addRequirements, getName, getRequirements, getSubsystem, initSendable, setName, setSubsystem, withName
-
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
-
Methods inherited from interface edu.wpi.first.wpilibj2.command.Command
alongWith, andThen, andThen, asProxy, beforeStarting, beforeStarting, cancel, deadlineWith, end, execute, hasRequirement, isScheduled, perpetually, raceWith, schedule, schedule, withInterrupt, withTimeout
-
-
-
-
Constructor Detail
-
ScheduleCommand
public ScheduleCommand(Command... toSchedule)
Creates a new ScheduleCommand that schedules the given commands when initialized.- Parameters:
toSchedule
- the commands to schedule
-
-
Method Detail
-
initialize
public void initialize()
Description copied from interface:Command
The initial subroutine of a command. Called once when the command is initially scheduled.
-
isFinished
public boolean isFinished()
Description copied from interface:Command
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.
-
runsWhenDisabled
public boolean runsWhenDisabled()
Description copied from interface:Command
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
-
-