Le planificateur de commandes

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.

Le CommandScheduler exécute aussi la méthode periodic() de chaque Subsystem enrégistré.

Utiliser le planificateur de commandes

Le CommandScheduler est un singleton, ce qui veux dire qu’il est une classe accessible globalement avec une seule instance. Donc, pour accéder au planificateur, l’utilisateur devra appeler la commande CommandScheduler.getInstance().

En général, l’utilisateur ne doit pas appeler les méthodes du planificateur directement - presque tout les méthodes importantes du planificateur ont des enveloppe de commodité ailleurs (p. ex. dans les interfaces Command et Subsystem).

Cependant, il y a une exception: l’utilisateur doit appeler CommandScheduler.getInstance().run() de la méthode robotPeriodic() de la classe Robot. Si ce n’est pas effectué, le planificateur ne s’exécutera jamais et le cadre d’application des commandes ne fonctionnera pas. Le modèle de projet orienté commande fourni inclus déjà cet appel.

La méthode schedule()

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()");

La séquence d’exécution du planificateur

Note

La méthode initialize() de chaque Command est appelée lorsque la commande est programmée, ce qui n’est pas forcément quand le planificateur s’exécute (sauf si cette commande est liée à un bouton).

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++).

Étape 1: exécuter les méthodes périodique des sous-systèmes

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    }

Étape 2: sonder les déclencheurs de planification de commande

Note

Pour plus d’informations sur le fonctionnement des liens de déclencheurs, voir Liaison de commandes à des déclencheurs

Deuxièmement, le planificateur sonde l’état de tous les déclencheurs enregistres pour voir si des nouvelles commandes qui ont été liées à ces déclencheurs devraient être planifiées. Si les conditions pour planifier une commande liée sont remplies, la commande est planifié et sa méthode initialize() est exécutée.

290    // Poll buttons for new commands to add.
291    loopCache.poll();
292    m_watchdog.addEpoch("buttons.run()");

Étape 3: exécuter/terminer les commandes planifiées

Troisièmement, le planificateur appelle la méthode execute() de chaque commande en cours d’exécution après avoir vérifié si la commande est terminé en appelant la méthode isFinished(). Si la commande est terminé, la méthode end() est appelée aussi, et la commande est dé-planifiée et ses sous-systèmes requis sont libérés.

Notez qui cette séquence d’appels est faite en ordre pour chaque commande - ainsi, une commande peut avoir sa méthode end() appelée avant qu’une autre ait sa méthode execute() appelée. Les commandes sont manipulées dans l’ordre dont elles ont été planifiées.

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    }

Étape 4: planifier les commandes par défaut

Finalement, chaque Subsystem enrégistré a sa commande par défaut planifiée (si elle existe). Notez que la méthode initialize() de la commande de défaut sera appelée à ce moment.

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    }

Désactiver le Planificateur

Le planificateur peut être désactiver en appelant CommandScheduler.getInstance().disable(). Quand il est désactivé, les commandes schedule() et run() du planificateur ne font rien.

Le planificateur peut être ré-activé en appelant CommandScheduler.getInstance().enable().

Méthodes d’évènement de commande

Parfois, il est souhaitable que le planificateur exécute une action personnalisée chaque fois qu’un certain événement de commande (initialisation, exécution ou fin) se produit. Cela peut être fait avec les méthodes suivantes :

  • 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));