Class Scheduler

java.lang.Object
org.wpilib.commands3.Scheduler
All Implemented Interfaces:
ProtobufSerializable, WPISerializable

public final class Scheduler extends Object implements ProtobufSerializable
Manages the lifecycles of Coroutine-based Commands. Commands may be scheduled directly using schedule(Command), or be bound to Triggers to automatically handle scheduling and cancellation based on internal or external events. User code is responsible for calling run() periodically to update trigger conditions and execute scheduled commands. Most often, this is done by overriding IterativeRobotBase.robotPeriodic() to include a call to Scheduler.getDefault().run():

 public class Robot extends TimedRobot {
   @Override
   public void robotPeriodic() {
     // Update the scheduler on every loop
     Scheduler.getDefault().run();
   }
 }
 

Danger

The scheduler must be used in a single-threaded program. Commands must be scheduled and canceled by the same thread that runs the scheduler, and cannot be run in a virtual thread.

Using the commands framework in a multithreaded environment can cause crashes in the Java virtual machine at any time, including on an official field during a match. The Java JIT compilers make assumptions that rely on coroutines being used on a single thread. Breaking those assumptions can cause incorrect JIT code to be generated with undefined behavior, potentially causing control issues or crashes deep in JIT-generated native code.

Normal concurrency constructs like locks, atomic references, and synchronized blocks or methods cannot save you.

Lifecycle

The run() method runs five steps:

  1. Call periodic sideload functions
  2. Poll all registered triggers to queue and cancel commands
  3. Queue default commands for any mechanisms without a running command. The queued commands can be superseded by any manual scheduling or commands scheduled by triggers in the next run.
  4. Start all queued commands. This happens after all triggers are checked in case multiple commands with conflicting requirements are queued in the same update; the last command to be queued takes precedence over the rest.
  5. Loop over all running commands, mounting and calling each in turn until they either exit or call Coroutine.yield(). Commands run in the order in which they were scheduled.

Telemetry

There are two mechanisms for telemetry for a scheduler. A protobuf serializer can be used to take a snapshot of a scheduler instance, and report what commands are queued (scheduled but have not yet started to run), commands that are running (along with timing data for each command), and total time spent in the most recent run() call. However, it cannot detect one-shot commands that are scheduled, run, and complete all in a single run() invocation - effectively, commands that never call Coroutine.yield() are invisible.

A second telemetry mechanism is provided by addEventListener(Consumer). The scheduler will issue events to all registered listeners when certain events occur (see SchedulerEvent for all event types). These events are emitted immediately and can be used to detect lifecycle events for all commands, including one-shots that would be invisible to the protobuf serializer. However, it is up to the user to log those events themselves.

  • Field Details

  • Method Details

    • getDefault

      public static Scheduler getDefault()
      Gets the default scheduler instance for use in a robot program. Unless otherwise specified, triggers and mechanisms will be registered with the default scheduler and require the default scheduler to run. However, triggers and mechanisms can be constructed to be registered with a specific scheduler instance, which may be useful for isolation for unit tests.
      Returns:
      the default scheduler instance.
    • createIndependentScheduler

      Creates a new scheduler object. Note that most built-in constructs like Trigger and CommandGenericHID will use the default scheduler instance unless they were explicitly constructed with a different scheduler instance. Teams should use the default instance for convenience; however, new scheduler instances can be useful for unit tests.
      Returns:
      a new scheduler instance that is independent of the default scheduler instance.
    • setDefaultCommand

      public void setDefaultCommand(Mechanism mechanism, Command defaultCommand)
      Sets the default command for a mechanism. The command must require that mechanism, and cannot require any other mechanisms.
      Parameters:
      mechanism - the mechanism for which to set the default command
      defaultCommand - the default command to execute on the mechanism
      Throws:
      IllegalArgumentException - if the command does not meet the requirements for being a default command
    • getDefaultCommandFor

      Gets the default command set for a mechanism.
      Parameters:
      mechanism - The mechanism
      Returns:
      The default command, or null if no default command was ever set
    • sideload

      public void sideload(Consumer<Coroutine> callback)
      Adds a callback to run as part of the scheduler. The callback should not manipulate or control any mechanisms, but can be used to log information, update data (such as simulations or LED data buffers), or perform some other helpful task. The callback is responsible for managing its own control flow and end conditions. If you want to run a single task periodically for the entire lifespan of the scheduler, use addPeriodic(Runnable).

      Note: Like commands, any loops in the callback must appropriately yield control back to the scheduler with Coroutine.yield() or risk stalling your program in an unrecoverable infinite loop!

      Parameters:
      callback - the callback to sideload
    • addPeriodic

      public void addPeriodic(Runnable callback)
      Adds a task to run repeatedly for as long as the scheduler runs. This internally handles the looping and control yielding necessary for proper function. The callback will run at the same periodic frequency as the scheduler.

      For example:

      
       scheduler.addPeriodic(() -> leds.setData(ledDataBuffer));
       scheduler.addPeriodic(() -> {
         SmartDashboard.putNumber("X", getX());
         SmartDashboard.putNumber("Y", getY());
       });
       
      Parameters:
      callback - the periodic function to run
    • schedule

      Schedules a command to run. If one command schedules another (a "parent" and "child"), the child command will be canceled when the parent command completes. It is not possible to fork a child command and have it live longer than its parent.

      Does nothing if the command is already scheduled or running, or requires at least one mechanism already used by a higher priority command.

      Parameters:
      command - the command to schedule
      Returns:
      the result of the scheduling attempt. See Scheduler.ScheduleResult for details.
      Throws:
      IllegalArgumentException - if scheduled by a command composition that has already scheduled another command that shares at least one required mechanism
    • cancel

      public void cancel(Command command)
      Cancels a command and any other command scheduled by it. This occurs immediately and does not need to wait for a call to run(). Any command that it scheduled will also be canceled to ensure commands within compositions do not continue to run.

      This has no effect if the given command is not currently scheduled or running.

      Parameters:
      command - the command to cancel
    • run

      public void run()
      Updates the command scheduler. This will run operations in the following order:
      1. Run sideloaded functions from sideload(Consumer) and addPeriodic(Runnable)
      2. Update trigger bindings to queue and cancel bound commands
      3. Queue default commands for mechanisms that do not have a queued or running command
      4. Promote queued commands to the running set
      5. For every command in the running set, mount and run that command until it calls Coroutine.yield() or exits

      This method is intended to be called in a periodic loop like IterativeRobotBase.robotPeriodic()

    • currentCommand

      Gets the currently executing command, or null if no command is currently executing.
      Returns:
      the currently executing command
    • isRunning

      public boolean isRunning(Command command)
      Checks if a command is currently running.
      Parameters:
      command - the command to check
      Returns:
      true if the command is running, false if not
    • isScheduled

      public boolean isScheduled(Command command)
      Checks if a command is currently scheduled to run, but is not yet running.
      Parameters:
      command - the command to check
      Returns:
      true if the command is scheduled to run, false if not
    • isScheduledOrRunning

      public boolean isScheduledOrRunning(Command command)
      Checks if a command is currently scheduled to run, or is already running.
      Parameters:
      command - the command to check
      Returns:
      true if the command is scheduled to run or is already running, false if not
    • getRunningCommands

      Gets the set of all currently running commands. Commands are returned in the order in which they were scheduled. The returned set is read-only.
      Returns:
      the currently running commands
    • getRunningCommandsFor

      Gets all the currently running commands that require a particular mechanism. Commands are returned in the order in which they were scheduled. The returned list is read-only.
      Parameters:
      mechanism - the mechanism to get the commands for
      Returns:
      the currently running commands that require the mechanism.
    • cancelAll

      public void cancelAll()
      Cancels all currently running and scheduled commands. All default commands will be scheduled on the next call to run(), unless a higher priority command is scheduled or triggered after cancelAll() is used.
    • getDefaultEventLoop

      An event loop used by the scheduler to poll triggers that schedule or cancel commands. This event loop is always polled on every call to run(). Custom event loops need to be bound to this one for synchronicity with the scheduler; however, they can always be polled manually before or after the call to run().
      Returns:
      the default event loop.
    • getQueuedCommands

      For internal use.
      Returns:
      The commands that have been scheduled but not yet started.
    • getParentOf

      public Command getParentOf(Command command)
      For internal use.
      Parameters:
      command - The command to check
      Returns:
      The command that forked the provided command. Null if the command is not a child of another command.
    • lastCommandRuntimeMs

      public double lastCommandRuntimeMs(Command command)
      Gets how long a command took to run in the previous cycle. If the command is not currently running, returns -1.
      Parameters:
      command - The command to check
      Returns:
      How long, in milliseconds, the command last took to execute.
    • totalRuntimeMs

      public double totalRuntimeMs(Command command)
      Gets how long a command has taken to run, in aggregate, since it was most recently scheduled. If the command is not currently running, returns -1.
      Parameters:
      command - The command to check
      Returns:
      How long, in milliseconds, the command has taken to execute in total
    • runId

      public int runId(Command command)
      Gets the unique run id for a scheduled or running command. If the command is not currently scheduled or running, this function returns 0.
      Parameters:
      command - The command to get the run ID for
      Returns:
      The run of the command
    • lastRuntimeMs

      public double lastRuntimeMs()
      Gets how long the scheduler took to process its most recent run() invocation, in milliseconds. Defaults to -1 if the scheduler has not yet run.
      Returns:
      How long, in milliseconds, the scheduler last took to execute.
    • addEventListener

      public void addEventListener(Consumer<? super SchedulerEvent> listener)
      Adds a listener to handle events that are emitted by the scheduler. Events are emitted when certain actions are taken by user code or by internal processing logic in the scheduler. Listeners should take care to be quick, simple, and not schedule or cancel commands, as that may cause inconsistent scheduler behavior or even cause a program crash.

      Listeners are primarily expected to be for data logging and telemetry. In particular, a one-shot command (one that never calls Coroutine.yield()) will never appear in the standard protobuf telemetry because it is scheduled, runs, and finishes all in a single scheduler cycle. However, SchedulerEvent.Scheduled,SchedulerEvent.Mounted, and SchedulerEvent.Completed events will be emitted corresponding to those actions, and user code can listen for and log such events.

      Parameters:
      listener - The listener to add. Cannot be null.
      Throws:
      NullPointerException - if given a null listener