CommandScheduler
- class commands2.CommandScheduler[source]
Bases:
Sendable
The scheduler responsible for running Commands. A Command-based robot should call
run()
on the singleton instance in its periodic block in order to run commands synchronously from the main loop. Subsystems should be registered with the scheduler usingregisterSubsystem()
in order for theircommands2.Subsystem.periodic()
methods to be called and for their default commands to be scheduled.Gets the scheduler instance.
- cancel(*commands: Command) None [source]
Cancels commands. The scheduler will only call
commands2.Command.end()
method of the canceled command withTrue
, indicating they were canceled (as opposed to finishing normally).Commands will be canceled regardless of InterruptionBehavior interruption behavior.
- Parameters:
commands – the commands to cancel
- clearComposedCommands() None [source]
Clears the list of composed commands, allowing all commands to be freely used again.
Warning
Using this haphazardly can result in unexpected/undesirable behavior. Do not use this unless you fully understand what you are doing.
- getActiveButtonLoop() EventLoop [source]
Get the active button poll.
- Returns:
a reference to the current EventLoop object polling buttons.
- getDefaultButtonLoop() EventLoop [source]
Get the default button poll.
- Returns:
a reference to the default EventLoop object polling buttons.
- getDefaultCommand(subsystem: Subsystem) Command | None [source]
Gets the default command associated with this subsystem. Null if this subsystem has no default command associated with it.
- Parameters:
subsystem – the subsystem to inquire about
- Returns:
the default command associated with the subsystem
- static getInstance() CommandScheduler [source]
Returns the Scheduler instance.
- Returns:
the instance
- initSendable(builder: wpiutil._wpiutil.SendableBuilder) None [source]
Initializes this Sendable object.
- Parameters:
builder – sendable builder
- isComposed(command: Command) bool [source]
Check if the given command has been composed.
- Parameters:
command – The command to check
- Returns:
true if composed
- isScheduled(*commands: Command) bool [source]
Whether the given commands are running. Note that this only works on commands that are directly scheduled by the scheduler; it will not work on commands inside compositions, as the scheduler does not see them.
- Parameters:
commands – the command to query
- Returns:
whether the command is currently scheduled
- onCommandExecute(action: Callable[[Command], Any]) None [source]
Adds an action to perform on the execution of any command by the scheduler.
- Parameters:
action – the action to perform
- onCommandFinish(action: Callable[[Command], Any]) None [source]
Adds an action to perform on the finishing of any command by the scheduler.
- Parameters:
action – the action to perform
- onCommandInitialize(action: Callable[[Command], Any]) None [source]
Adds an action to perform on the initialization of any command by the scheduler.
- Parameters:
action – the action to perform
- onCommandInterrupt(action: Callable[[Command], Any]) None [source]
Adds an action to perform on the interruption of any command by the scheduler.
- Parameters:
action – the action to perform
- onCommandInterruptWithCause(action: Callable[[Command, Command | None], Any]) None [source]
Adds an action to perform on the interruption of any command by the scheduler. The action receives the interrupted command and the command that interrupted it
- Parameters:
action – the action to perform
- registerComposedCommands(commands: Iterable[Command]) None [source]
Register commands as composed. An exception will be thrown if these commands are scheduled directly or added to a composition.
- Parameters:
commands – the commands to register
- Raises:
IllegalCommandUse – if the given commands have already been composed.
- registerSubsystem(*subsystems: Subsystem) None [source]
Registers subsystems with the scheduler. This must be called for the subsystem’s periodic block to run when the scheduler is run, and for the subsystem’s default command to be scheduled. It is recommended to call this from the constructor of your subsystem implementations.
- Parameters:
subsystems – the subsystem to register
- removeComposedCommand(command: Command) None [source]
Removes a single command from the list of composed commands, allowing it to be freely used again.
Warning
Using this haphazardly can result in unexpected/undesirable behavior. Do not use this unless you fully understand what you are doing.
- Parameters:
command – the command to remove from the list of grouped commands
- removeDefaultCommand(subsystem: Subsystem) None [source]
Removes the default command for a subsystem. The current default command will run until another command is scheduled that requires the subsystem, at which point the current default command will not be re-scheduled.
- Parameters:
subsystem – the subsystem whose default command will be removed
- requireNotComposed(*commands: Command) None [source]
Requires that the specified command hasn’t been already added to a composition.
- Parameters:
commands – The commands to check
- Raises:
IllegalCommandUse – if the given commands have already been composed.
- requireNotComposedOrScheduled(*commands: Command) None [source]
Requires that the specified command hasn’t already been added to a composition, and is not currently scheduled.
- Parameters:
command – The command to check
- Raises:
IllegalCommandUse – if the given command has already been composed or scheduled.
- requiring(subsystem: Subsystem) Command | None [source]
Returns the command currently requiring a given subsystem. None if no command is currently requiring the subsystem
- Parameters:
subsystem – the subsystem to be inquired about
- Returns:
the command currently requiring the subsystem, or None if no command is currently scheduled
- static resetInstance() None [source]
Resets the scheduler instance, which is useful for testing purposes. This should not be called by user code.
- run() None [source]
Runs a single iteration of the scheduler. The execution occurs in the following order:
Subsystem periodic methods are called.
Button bindings are polled, and new commands are scheduled from them.
Currently-scheduled commands are executed.
End conditions are checked on currently-scheduled commands, and commands that are finished have their end methods called and are removed.
Any subsystems not being used as requirements have their default methods started.
- schedule(*commands: Command) None [source]
Schedules a command for execution. Does nothing if the command is already scheduled. If a command’s requirements are not available, it will only be started if all the commands currently using those requirements have been scheduled as interruptible. If this is the case, they will be interrupted and the command will be scheduled.
- Parameters:
commands – the commands to schedule.
- setActiveButtonLoop(loop: EventLoop) None [source]
Replace the button poll with another one.
- Parameters:
loop – the new button polling loop object.
- setDefaultCommand(subsystem: Subsystem, defaultCommand: Command) None [source]
Sets the default command for a subsystem. Registers that subsystem if it is not already registered. Default commands will run whenever there is no other command currently scheduled that requires the subsystem. Default commands should be written to never end (i.e. their
commands2.Command.isFinished()
method should return False), as they would simply be re-scheduled if they do. Default commands must also require their subsystem.- Parameters:
subsystem – the subsystem whose default command will be set
defaultCommand – the default command to associate with the subsystem
- setPeriod(period: float) None [source]
Changes the period of the loop overrun watchdog. This should be kept in sync with the TimedRobot period.
- Parameters:
period – Period in seconds.