The Command Scheduler

The CommandScheduler (Java, C++) is the class responsible for actually running commands. Each iteration (ordinarily once per 20ms), the scheduler polls all registered buttons, schedules commands for execution accordingly, runs the command bodies of all scheduled commands, and ends those commands that have finished or are interrupted.

The CommandScheduler also runs the periodic() method of each registered Subsystem.

Using the Command Scheduler

The CommandScheduler is a singleton, meaning that it is a globally-accessible class with only one instance. Accordingly, in order to access the scheduler, users must call the CommandScheduler.getInstance() command.

For the most part, users do not have to call scheduler methods directly - almost all important scheduler methods have convenience wrappers elsewhere (e.g. in the Command and Subsystem classes).

However, there is one exception: users must call CommandScheduler.getInstance().run() from the robotPeriodic() method of their Robot class. If this is not done, the scheduler will never run, and the command framework will not work. The provided command-based project template has this call already included.

The schedule() Method

To schedule a command, users call the schedule() method (Java, C++). This method takes a command, and attempts to add it to list of currently-running commands, pending whether it is already running or whether its requirements are available. If it is added, its initialize() method is called.

This method walks through the following steps:

  1. Verifies that the command isn’t in a composition.

  2. No-op if scheduler is disabled, command is already scheduled, or robot is disabled and command doesn’t <commands:runsWhenDisabled>.

  3. If requirements are in use: * If all conflicting commands are interruptible, cancel them. * If not, don’t schedule the new command.

  4. Call initialize().

202  private void schedule(Command command) {
203    if (command == null) {
204      DriverStation.reportWarning("Tried to schedule a null command", true);
205      return;
206    }
207    if (m_inRunLoop) {
208      m_toSchedule.add(command);
209      return;
210    }
211
212    requireNotComposed(command);
213
214    // Do nothing if the scheduler is disabled, the robot is disabled and the command doesn't
215    // run when disabled, or the command is already scheduled.
216    if (m_disabled
217        || isScheduled(command)
218        || RobotState.isDisabled() && !command.runsWhenDisabled()) {
219      return;
220    }
221
222    Set<Subsystem> requirements = command.getRequirements();
223
224    // Schedule the command if the requirements are not currently in-use.
225    if (Collections.disjoint(m_requirements.keySet(), requirements)) {
226      initCommand(command, requirements);
227    } else {
228      // Else check if the requirements that are in use have all have interruptible commands,
229      // and if so, interrupt those commands and schedule the new command.
230      for (Subsystem requirement : requirements) {
231        Command requiring = requiring(requirement);
232        if (requiring != null
233            && requiring.getInterruptionBehavior() == InterruptionBehavior.kCancelIncoming) {
234          return;
235        }
236      }
237      for (Subsystem requirement : requirements) {
238        Command requiring = requiring(requirement);
239        if (requiring != null) {
240          cancel(requiring);
241        }
242      }
243      initCommand(command, requirements);
244    }
245  }
181  private void initCommand(Command command, Set<Subsystem> requirements) {
182    m_scheduledCommands.add(command);
183    for (Subsystem requirement : requirements) {
184      m_requirements.put(requirement, command);
185    }
186    command.initialize();
187    for (Consumer<Command> action : m_initActions) {
188      action.accept(command);
189    }
190
191    m_watchdog.addEpoch(command.getName() + ".initialize()");
114void CommandScheduler::Schedule(Command* command) {
115  if (m_impl->inRunLoop) {
116    m_impl->toSchedule.emplace_back(command);
117    return;
118  }
119
120  RequireUngrouped(command);
121
122  if (m_impl->disabled || m_impl->scheduledCommands.contains(command) ||
123      (frc::RobotState::IsDisabled() && !command->RunsWhenDisabled())) {
124    return;
125  }
126
127  const auto& requirements = command->GetRequirements();
128
129  wpi::SmallVector<Command*, 8> intersection;
130
131  bool isDisjoint = true;
132  bool allInterruptible = true;
133  for (auto&& i1 : m_impl->requirements) {
134    if (requirements.find(i1.first) != requirements.end()) {
135      isDisjoint = false;
136      allInterruptible &= (i1.second->GetInterruptionBehavior() ==
137                           Command::InterruptionBehavior::kCancelSelf);
138      intersection.emplace_back(i1.second);
139    }
140  }
141
142  if (isDisjoint || allInterruptible) {
143    if (allInterruptible) {
144      for (auto&& cmdToCancel : intersection) {
145        Cancel(cmdToCancel);
146      }
147    }
148    m_impl->scheduledCommands.insert(command);
149    for (auto&& requirement : requirements) {
150      m_impl->requirements[requirement] = command;
151    }
152    command->Initialize();
153    for (auto&& action : m_impl->initActions) {
154      action(*command);
155    }
156    m_watchdog.AddEpoch(command->GetName() + ".Initialize()");
157  }
158}

The Scheduler Run Sequence

Nota

The initialize() method of each Command is called when the command is scheduled, which is not necessarily when the scheduler runs (unless that command is bound to a button).

What does a single iteration of the scheduler’s run() method (Java, C++) actually do? The following section walks through the logic of a scheduler iteration. For the full implementation, see the source code (Java, C++).

Step 1: Run Subsystem Periodic Methods

First, the scheduler runs the periodic() method of each registered Subsystem. In simulation, each subsystem’s simulationPeriodic() method is called as well.

278    // Run the periodic method of all registered subsystems.
279    for (Subsystem subsystem : m_subsystems.keySet()) {
280      subsystem.periodic();
281      if (RobotBase.isSimulation()) {
282        subsystem.simulationPeriodic();
283      }
284      m_watchdog.addEpoch(subsystem.getClass().getSimpleName() + ".periodic()");
285    }
183  // Run the periodic method of all registered subsystems.
184  for (auto&& subsystem : m_impl->subsystems) {
185    subsystem.getFirst()->Periodic();
186    if constexpr (frc::RobotBase::IsSimulation()) {
187      subsystem.getFirst()->SimulationPeriodic();
188    }
189    m_watchdog.AddEpoch("Subsystem Periodic()");
190  }

Step 2: Poll Command Scheduling Triggers

Nota

For more information on how trigger bindings work, see Binding Commands to Triggers

Secondly, the scheduler polls the state of all registered triggers to see if any new commands that have been bound to those triggers should be scheduled. If the conditions for scheduling a bound command are met, the command is scheduled and its Initialize() method is run.

290    // Poll buttons for new commands to add.
291    loopCache.poll();
292    m_watchdog.addEpoch("buttons.run()");
195  // Poll buttons for new commands to add.
196  loopCache->Poll();
197  m_watchdog.AddEpoch("buttons.Run()");

Step 3: Run/Finish Scheduled Commands

Thirdly, the scheduler calls the execute() method of each currently-scheduled command, and then checks whether the command has finished by calling the isFinished() method. If the command has finished, the end() method is also called, and the command is de-scheduled and its required subsystems are freed.

Note that this sequence of calls is done in order for each command - thus, one command may have its end() method called before another has its execute() method called. Commands are handled in the order they were scheduled.

295    // Run scheduled commands, remove finished commands.
296    for (Iterator<Command> iterator = m_scheduledCommands.iterator(); iterator.hasNext(); ) {
297      Command command = iterator.next();
298
299      if (!command.runsWhenDisabled() && RobotState.isDisabled()) {
300        command.end(true);
301        for (Consumer<Command> action : m_interruptActions) {
302          action.accept(command);
303        }
304        m_requirements.keySet().removeAll(command.getRequirements());
305        iterator.remove();
306        m_watchdog.addEpoch(command.getName() + ".end(true)");
307        continue;
308      }
309
310      command.execute();
311      for (Consumer<Command> action : m_executeActions) {
312        action.accept(command);
313      }
314      m_watchdog.addEpoch(command.getName() + ".execute()");
315      if (command.isFinished()) {
316        command.end(false);
317        for (Consumer<Command> action : m_finishActions) {
318          action.accept(command);
319        }
320        iterator.remove();
321
322        m_requirements.keySet().removeAll(command.getRequirements());
323        m_watchdog.addEpoch(command.getName() + ".end(false)");
324      }
325    }
201  for (Command* command : m_impl->scheduledCommands) {
202    if (!command->RunsWhenDisabled() && frc::RobotState::IsDisabled()) {
203      Cancel(command);
204      continue;
205    }
206
207    command->Execute();
208    for (auto&& action : m_impl->executeActions) {
209      action(*command);
210    }
211    m_watchdog.AddEpoch(command->GetName() + ".Execute()");
212
213    if (command->IsFinished()) {
214      command->End(false);
215      for (auto&& action : m_impl->finishActions) {
216        action(*command);
217      }
218
219      for (auto&& requirement : command->GetRequirements()) {
220        m_impl->requirements.erase(requirement);
221      }
222
223      m_impl->scheduledCommands.erase(command);
224      m_watchdog.AddEpoch(command->GetName() + ".End(false)");
225    }
226  }

Step 4: Schedule Default Commands

Finally, any registered Subsystem has its default command scheduled (if it has one). Note that the initialize() method of the default command will be called at this time.

340    // Add default commands for un-required registered subsystems.
341    for (Map.Entry<Subsystem, Command> subsystemCommand : m_subsystems.entrySet()) {
342      if (!m_requirements.containsKey(subsystemCommand.getKey())
343          && subsystemCommand.getValue() != null) {
344        schedule(subsystemCommand.getValue());
345      }
346    }
240  // Add default commands for un-required registered subsystems.
241  for (auto&& subsystem : m_impl->subsystems) {
242    auto s = m_impl->requirements.find(subsystem.getFirst());
243    if (s == m_impl->requirements.end() && subsystem.getSecond()) {
244      Schedule({subsystem.getSecond().get()});
245    }
246  }

Disabling the Scheduler

The scheduler can be disabled by calling CommandScheduler.getInstance().disable(). When disabled, the scheduler’s schedule() and run() commands will not do anything.

The scheduler may be re-enabled by calling CommandScheduler.getInstance().enable().

Command Event Methods

Occasionally, it is desirable to have the scheduler execute a custom action whenever a certain command event (initialization, execution, or ending) occurs. This can be done with the following methods:

  • onCommandInitialize (Java, C++) runs a specified action whenever a command is initialized.

  • onCommandExecute (Java, C++) runs a specified action whenever a command is executed.

  • onCommandFinish (Java, C++) runs a specified action whenever a command finishes normally (i.e. the isFinished() method returned true).

  • onCommandInterrupt (Java, C++) runs a specified action whenever a command is interrupted (i.e. by being explicitly canceled or by another command that shares one of its requirements).

A typical use-case for these methods is adding markers in an event log whenever a command scheduling event takes place, as demonstrated in the following code from the HatchbotInlined example project (Java, C++):

73    // Set the scheduler to log Shuffleboard events for command initialize, interrupt, finish
74    CommandScheduler.getInstance()
75        .onCommandInitialize(
76            command ->
77                Shuffleboard.addEventMarker(
78                    "Command initialized", command.getName(), EventImportance.kNormal));
79    CommandScheduler.getInstance()
80        .onCommandInterrupt(
81            command ->
82                Shuffleboard.addEventMarker(
83                    "Command interrupted", command.getName(), EventImportance.kNormal));
84    CommandScheduler.getInstance()
85        .onCommandFinish(
86            command ->
87                Shuffleboard.addEventMarker(
88                    "Command finished", command.getName(), EventImportance.kNormal));
23  // Log Shuffleboard events for command initialize, execute, finish, interrupt
24  frc2::CommandScheduler::GetInstance().OnCommandInitialize(
25      [](const frc2::Command& command) {
26        frc::Shuffleboard::AddEventMarker(
27            "Command initialized", command.GetName(),
28            frc::ShuffleboardEventImportance::kNormal);
29      });
30  frc2::CommandScheduler::GetInstance().OnCommandExecute(
31      [](const frc2::Command& command) {
32        frc::Shuffleboard::AddEventMarker(
33            "Command executed", command.GetName(),
34            frc::ShuffleboardEventImportance::kNormal);
35      });
36  frc2::CommandScheduler::GetInstance().OnCommandFinish(
37      [](const frc2::Command& command) {
38        frc::Shuffleboard::AddEventMarker(
39            "Command finished", command.GetName(),
40            frc::ShuffleboardEventImportance::kNormal);
41      });
42  frc2::CommandScheduler::GetInstance().OnCommandInterrupt(
43      [](const frc2::Command& command) {
44        frc::Shuffleboard::AddEventMarker(
45            "Command interrupted", command.GetName(),
46            frc::ShuffleboardEventImportance::kNormal);
47      });