001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.wpilibj2.command;
006
007import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
008
009import edu.wpi.first.hal.FRCNetComm.tInstances;
010import edu.wpi.first.hal.FRCNetComm.tResourceType;
011import edu.wpi.first.hal.HAL;
012import edu.wpi.first.networktables.IntegerArrayEntry;
013import edu.wpi.first.networktables.IntegerArrayPublisher;
014import edu.wpi.first.networktables.IntegerArrayTopic;
015import edu.wpi.first.networktables.NTSendable;
016import edu.wpi.first.networktables.NTSendableBuilder;
017import edu.wpi.first.networktables.StringArrayPublisher;
018import edu.wpi.first.networktables.StringArrayTopic;
019import edu.wpi.first.util.sendable.SendableRegistry;
020import edu.wpi.first.wpilibj.DriverStation;
021import edu.wpi.first.wpilibj.RobotBase;
022import edu.wpi.first.wpilibj.RobotState;
023import edu.wpi.first.wpilibj.TimedRobot;
024import edu.wpi.first.wpilibj.Watchdog;
025import edu.wpi.first.wpilibj.event.EventLoop;
026import edu.wpi.first.wpilibj.livewindow.LiveWindow;
027import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior;
028import java.util.ArrayList;
029import java.util.Collection;
030import java.util.Collections;
031import java.util.Iterator;
032import java.util.LinkedHashMap;
033import java.util.LinkedHashSet;
034import java.util.List;
035import java.util.Map;
036import java.util.Set;
037import java.util.WeakHashMap;
038import java.util.function.Consumer;
039
040/**
041 * The scheduler responsible for running {@link Command}s. A Command-based robot should call {@link
042 * CommandScheduler#run()} on the singleton instance in its periodic block in order to run commands
043 * synchronously from the main loop. Subsystems should be registered with the scheduler using {@link
044 * CommandScheduler#registerSubsystem(Subsystem...)} in order for their {@link Subsystem#periodic()}
045 * methods to be called and for their default commands to be scheduled.
046 *
047 * <p>This class is provided by the NewCommands VendorDep
048 */
049public final class CommandScheduler implements NTSendable, AutoCloseable {
050  /** The Singleton Instance. */
051  private static CommandScheduler instance;
052
053  /**
054   * Returns the Scheduler instance.
055   *
056   * @return the instance
057   */
058  public static synchronized CommandScheduler getInstance() {
059    if (instance == null) {
060      instance = new CommandScheduler();
061    }
062    return instance;
063  }
064
065  private final Set<Command> m_composedCommands = Collections.newSetFromMap(new WeakHashMap<>());
066
067  // A set of the currently-running commands.
068  private final Set<Command> m_scheduledCommands = new LinkedHashSet<>();
069
070  // A map from required subsystems to their requiring commands. Also used as a set of the
071  // currently-required subsystems.
072  private final Map<Subsystem, Command> m_requirements = new LinkedHashMap<>();
073
074  // A map from subsystems registered with the scheduler to their default commands.  Also used
075  // as a list of currently-registered subsystems.
076  private final Map<Subsystem, Command> m_subsystems = new LinkedHashMap<>();
077
078  private final EventLoop m_defaultButtonLoop = new EventLoop();
079  // The set of currently-registered buttons that will be polled every iteration.
080  private EventLoop m_activeButtonLoop = m_defaultButtonLoop;
081
082  private boolean m_disabled;
083
084  // Lists of user-supplied actions to be executed on scheduling events for every command.
085  private final List<Consumer<Command>> m_initActions = new ArrayList<>();
086  private final List<Consumer<Command>> m_executeActions = new ArrayList<>();
087  private final List<Consumer<Command>> m_interruptActions = new ArrayList<>();
088  private final List<Consumer<Command>> m_finishActions = new ArrayList<>();
089
090  // Flag and queues for avoiding ConcurrentModificationException if commands are
091  // scheduled/canceled during run
092  private boolean m_inRunLoop;
093  private final Set<Command> m_toSchedule = new LinkedHashSet<>();
094  private final List<Command> m_toCancel = new ArrayList<>();
095
096  private final Watchdog m_watchdog = new Watchdog(TimedRobot.kDefaultPeriod, () -> {});
097
098  CommandScheduler() {
099    HAL.report(tResourceType.kResourceType_Command, tInstances.kCommand2_Scheduler);
100    SendableRegistry.addLW(this, "Scheduler");
101    LiveWindow.setEnabledListener(
102        () -> {
103          disable();
104          cancelAll();
105        });
106    LiveWindow.setDisabledListener(
107        () -> {
108          enable();
109        });
110  }
111
112  /**
113   * Changes the period of the loop overrun watchdog. This should be kept in sync with the
114   * TimedRobot period.
115   *
116   * @param period Period in seconds.
117   */
118  public void setPeriod(double period) {
119    m_watchdog.setTimeout(period);
120  }
121
122  @Override
123  public void close() {
124    SendableRegistry.remove(this);
125    LiveWindow.setEnabledListener(null);
126    LiveWindow.setDisabledListener(null);
127  }
128
129  /**
130   * Get the default button poll.
131   *
132   * @return a reference to the default {@link EventLoop} object polling buttons.
133   */
134  public EventLoop getDefaultButtonLoop() {
135    return m_defaultButtonLoop;
136  }
137
138  /**
139   * Get the active button poll.
140   *
141   * @return a reference to the current {@link EventLoop} object polling buttons.
142   */
143  public EventLoop getActiveButtonLoop() {
144    return m_activeButtonLoop;
145  }
146
147  /**
148   * Replace the button poll with another one.
149   *
150   * @param loop the new button polling loop object.
151   */
152  public void setActiveButtonLoop(EventLoop loop) {
153    m_activeButtonLoop =
154        requireNonNullParam(loop, "loop", "CommandScheduler" + ".replaceButtonEventLoop");
155  }
156
157  /**
158   * Adds a button binding to the scheduler, which will be polled to schedule commands.
159   *
160   * @param button The button to add
161   * @deprecated Use {@link edu.wpi.first.wpilibj2.command.button.Trigger}
162   */
163  @Deprecated(since = "2023")
164  public void addButton(Runnable button) {
165    m_activeButtonLoop.bind(requireNonNullParam(button, "button", "addButton"));
166  }
167
168  /**
169   * Removes all button bindings from the scheduler.
170   *
171   * @deprecated call {@link EventLoop#clear()} on {@link #getActiveButtonLoop()} directly instead.
172   */
173  @Deprecated(since = "2023")
174  public void clearButtons() {
175    m_activeButtonLoop.clear();
176  }
177
178  /**
179   * Initializes a given command, adds its requirements to the list, and performs the init actions.
180   *
181   * @param command The command to initialize
182   * @param requirements The command requirements
183   */
184  private void initCommand(Command command, Set<Subsystem> requirements) {
185    m_scheduledCommands.add(command);
186    for (Subsystem requirement : requirements) {
187      m_requirements.put(requirement, command);
188    }
189    command.initialize();
190    for (Consumer<Command> action : m_initActions) {
191      action.accept(command);
192    }
193
194    m_watchdog.addEpoch(command.getName() + ".initialize()");
195  }
196
197  /**
198   * Schedules a command for execution. Does nothing if the command is already scheduled. If a
199   * command's requirements are not available, it will only be started if all the commands currently
200   * using those requirements have been scheduled as interruptible. If this is the case, they will
201   * be interrupted and the command will be scheduled.
202   *
203   * @param command the command to schedule. If null, no-op.
204   */
205  private void schedule(Command command) {
206    if (command == null) {
207      DriverStation.reportWarning("Tried to schedule a null command", true);
208      return;
209    }
210    if (m_inRunLoop) {
211      m_toSchedule.add(command);
212      return;
213    }
214
215    requireNotComposed(command);
216
217    // Do nothing if the scheduler is disabled, the robot is disabled and the command doesn't
218    // run when disabled, or the command is already scheduled.
219    if (m_disabled
220        || isScheduled(command)
221        || RobotState.isDisabled() && !command.runsWhenDisabled()) {
222      return;
223    }
224
225    Set<Subsystem> requirements = command.getRequirements();
226
227    // Schedule the command if the requirements are not currently in-use.
228    if (Collections.disjoint(m_requirements.keySet(), requirements)) {
229      initCommand(command, requirements);
230    } else {
231      // Else check if the requirements that are in use have all have interruptible commands,
232      // and if so, interrupt those commands and schedule the new command.
233      for (Subsystem requirement : requirements) {
234        Command requiring = requiring(requirement);
235        if (requiring != null
236            && requiring.getInterruptionBehavior() == InterruptionBehavior.kCancelIncoming) {
237          return;
238        }
239      }
240      for (Subsystem requirement : requirements) {
241        Command requiring = requiring(requirement);
242        if (requiring != null) {
243          cancel(requiring);
244        }
245      }
246      initCommand(command, requirements);
247    }
248  }
249
250  /**
251   * Schedules multiple commands for execution. Does nothing for commands already scheduled.
252   *
253   * @param commands the commands to schedule. No-op on null.
254   */
255  public void schedule(Command... commands) {
256    for (Command command : commands) {
257      schedule(command);
258    }
259  }
260
261  /**
262   * Runs a single iteration of the scheduler. The execution occurs in the following order:
263   *
264   * <p>Subsystem periodic methods are called.
265   *
266   * <p>Button bindings are polled, and new commands are scheduled from them.
267   *
268   * <p>Currently-scheduled commands are executed.
269   *
270   * <p>End conditions are checked on currently-scheduled commands, and commands that are finished
271   * have their end methods called and are removed.
272   *
273   * <p>Any subsystems not being used as requirements have their default methods started.
274   */
275  public void run() {
276    if (m_disabled) {
277      return;
278    }
279    m_watchdog.reset();
280
281    // Run the periodic method of all registered subsystems.
282    for (Subsystem subsystem : m_subsystems.keySet()) {
283      subsystem.periodic();
284      if (RobotBase.isSimulation()) {
285        subsystem.simulationPeriodic();
286      }
287      m_watchdog.addEpoch(subsystem.getClass().getSimpleName() + ".periodic()");
288    }
289
290    // Cache the active instance to avoid concurrency problems if setActiveLoop() is called from
291    // inside the button bindings.
292    EventLoop loopCache = m_activeButtonLoop;
293    // Poll buttons for new commands to add.
294    loopCache.poll();
295    m_watchdog.addEpoch("buttons.run()");
296
297    m_inRunLoop = true;
298    // Run scheduled commands, remove finished commands.
299    for (Iterator<Command> iterator = m_scheduledCommands.iterator(); iterator.hasNext(); ) {
300      Command command = iterator.next();
301
302      if (!command.runsWhenDisabled() && RobotState.isDisabled()) {
303        command.end(true);
304        for (Consumer<Command> action : m_interruptActions) {
305          action.accept(command);
306        }
307        m_requirements.keySet().removeAll(command.getRequirements());
308        iterator.remove();
309        m_watchdog.addEpoch(command.getName() + ".end(true)");
310        continue;
311      }
312
313      command.execute();
314      for (Consumer<Command> action : m_executeActions) {
315        action.accept(command);
316      }
317      m_watchdog.addEpoch(command.getName() + ".execute()");
318      if (command.isFinished()) {
319        command.end(false);
320        for (Consumer<Command> action : m_finishActions) {
321          action.accept(command);
322        }
323        iterator.remove();
324
325        m_requirements.keySet().removeAll(command.getRequirements());
326        m_watchdog.addEpoch(command.getName() + ".end(false)");
327      }
328    }
329    m_inRunLoop = false;
330
331    // Schedule/cancel commands from queues populated during loop
332    for (Command command : m_toSchedule) {
333      schedule(command);
334    }
335
336    for (Command command : m_toCancel) {
337      cancel(command);
338    }
339
340    m_toSchedule.clear();
341    m_toCancel.clear();
342
343    // Add default commands for un-required registered subsystems.
344    for (Map.Entry<Subsystem, Command> subsystemCommand : m_subsystems.entrySet()) {
345      if (!m_requirements.containsKey(subsystemCommand.getKey())
346          && subsystemCommand.getValue() != null) {
347        schedule(subsystemCommand.getValue());
348      }
349    }
350
351    m_watchdog.disable();
352    if (m_watchdog.isExpired()) {
353      System.out.println("CommandScheduler loop overrun");
354      m_watchdog.printEpochs();
355    }
356  }
357
358  /**
359   * Registers subsystems with the scheduler. This must be called for the subsystem's periodic block
360   * to run when the scheduler is run, and for the subsystem's default command to be scheduled. It
361   * is recommended to call this from the constructor of your subsystem implementations.
362   *
363   * @param subsystems the subsystem to register
364   */
365  public void registerSubsystem(Subsystem... subsystems) {
366    for (Subsystem subsystem : subsystems) {
367      if (subsystem == null) {
368        DriverStation.reportWarning("Tried to register a null subsystem", true);
369        continue;
370      }
371      if (m_subsystems.containsKey(subsystem)) {
372        DriverStation.reportWarning("Tried to register an already-registered subsystem", true);
373        continue;
374      }
375      m_subsystems.put(subsystem, null);
376    }
377  }
378
379  /**
380   * Un-registers subsystems with the scheduler. The subsystem will no longer have its periodic
381   * block called, and will not have its default command scheduled.
382   *
383   * @param subsystems the subsystem to un-register
384   */
385  public void unregisterSubsystem(Subsystem... subsystems) {
386    m_subsystems.keySet().removeAll(Set.of(subsystems));
387  }
388
389  /**
390   * Sets the default command for a subsystem. Registers that subsystem if it is not already
391   * registered. Default commands will run whenever there is no other command currently scheduled
392   * that requires the subsystem. Default commands should be written to never end (i.e. their {@link
393   * Command#isFinished()} method should return false), as they would simply be re-scheduled if they
394   * do. Default commands must also require their subsystem.
395   *
396   * @param subsystem the subsystem whose default command will be set
397   * @param defaultCommand the default command to associate with the subsystem
398   */
399  public void setDefaultCommand(Subsystem subsystem, Command defaultCommand) {
400    if (subsystem == null) {
401      DriverStation.reportWarning("Tried to set a default command for a null subsystem", true);
402      return;
403    }
404    if (defaultCommand == null) {
405      DriverStation.reportWarning("Tried to set a null default command", true);
406      return;
407    }
408
409    requireNotComposed(defaultCommand);
410
411    if (!defaultCommand.getRequirements().contains(subsystem)) {
412      throw new IllegalArgumentException("Default commands must require their subsystem!");
413    }
414
415    if (defaultCommand.getInterruptionBehavior() == InterruptionBehavior.kCancelIncoming) {
416      DriverStation.reportWarning(
417          "Registering a non-interruptible default command!\n"
418              + "This will likely prevent any other commands from requiring this subsystem.",
419          true);
420      // Warn, but allow -- there might be a use case for this.
421    }
422
423    m_subsystems.put(subsystem, defaultCommand);
424  }
425
426  /**
427   * Removes the default command for a subsystem. The current default command will run until another
428   * command is scheduled that requires the subsystem, at which point the current default command
429   * will not be re-scheduled.
430   *
431   * @param subsystem the subsystem whose default command will be removed
432   */
433  public void removeDefaultCommand(Subsystem subsystem) {
434    if (subsystem == null) {
435      DriverStation.reportWarning("Tried to remove a default command for a null subsystem", true);
436      return;
437    }
438
439    m_subsystems.put(subsystem, null);
440  }
441
442  /**
443   * Gets the default command associated with this subsystem. Null if this subsystem has no default
444   * command associated with it.
445   *
446   * @param subsystem the subsystem to inquire about
447   * @return the default command associated with the subsystem
448   */
449  public Command getDefaultCommand(Subsystem subsystem) {
450    return m_subsystems.get(subsystem);
451  }
452
453  /**
454   * Cancels commands. The scheduler will only call {@link Command#end(boolean)} method of the
455   * canceled command with {@code true}, indicating they were canceled (as opposed to finishing
456   * normally).
457   *
458   * <p>Commands will be canceled regardless of {@link InterruptionBehavior interruption behavior}.
459   *
460   * @param commands the commands to cancel
461   */
462  public void cancel(Command... commands) {
463    if (m_inRunLoop) {
464      m_toCancel.addAll(List.of(commands));
465      return;
466    }
467
468    for (Command command : commands) {
469      if (command == null) {
470        DriverStation.reportWarning("Tried to cancel a null command", true);
471        continue;
472      }
473      if (!isScheduled(command)) {
474        continue;
475      }
476
477      m_scheduledCommands.remove(command);
478      m_requirements.keySet().removeAll(command.getRequirements());
479      command.end(true);
480      for (Consumer<Command> action : m_interruptActions) {
481        action.accept(command);
482      }
483      m_watchdog.addEpoch(command.getName() + ".end(true)");
484    }
485  }
486
487  /** Cancels all commands that are currently scheduled. */
488  public void cancelAll() {
489    // Copy to array to avoid concurrent modification.
490    cancel(m_scheduledCommands.toArray(new Command[0]));
491  }
492
493  /**
494   * Whether the given commands are running. Note that this only works on commands that are directly
495   * scheduled by the scheduler; it will not work on commands inside compositions, as the scheduler
496   * does not see them.
497   *
498   * @param commands the command to query
499   * @return whether the command is currently scheduled
500   */
501  public boolean isScheduled(Command... commands) {
502    return m_scheduledCommands.containsAll(Set.of(commands));
503  }
504
505  /**
506   * Returns the command currently requiring a given subsystem. Null if no command is currently
507   * requiring the subsystem
508   *
509   * @param subsystem the subsystem to be inquired about
510   * @return the command currently requiring the subsystem, or null if no command is currently
511   *     scheduled
512   */
513  public Command requiring(Subsystem subsystem) {
514    return m_requirements.get(subsystem);
515  }
516
517  /** Disables the command scheduler. */
518  public void disable() {
519    m_disabled = true;
520  }
521
522  /** Enables the command scheduler. */
523  public void enable() {
524    m_disabled = false;
525  }
526
527  /**
528   * Adds an action to perform on the initialization of any command by the scheduler.
529   *
530   * @param action the action to perform
531   */
532  public void onCommandInitialize(Consumer<Command> action) {
533    m_initActions.add(requireNonNullParam(action, "action", "onCommandInitialize"));
534  }
535
536  /**
537   * Adds an action to perform on the execution of any command by the scheduler.
538   *
539   * @param action the action to perform
540   */
541  public void onCommandExecute(Consumer<Command> action) {
542    m_executeActions.add(requireNonNullParam(action, "action", "onCommandExecute"));
543  }
544
545  /**
546   * Adds an action to perform on the interruption of any command by the scheduler.
547   *
548   * @param action the action to perform
549   */
550  public void onCommandInterrupt(Consumer<Command> action) {
551    m_interruptActions.add(requireNonNullParam(action, "action", "onCommandInterrupt"));
552  }
553
554  /**
555   * Adds an action to perform on the finishing of any command by the scheduler.
556   *
557   * @param action the action to perform
558   */
559  public void onCommandFinish(Consumer<Command> action) {
560    m_finishActions.add(requireNonNullParam(action, "action", "onCommandFinish"));
561  }
562
563  /**
564   * Register commands as composed. An exception will be thrown if these commands are scheduled
565   * directly or added to a composition.
566   *
567   * @param commands the commands to register
568   * @throws IllegalArgumentException if the given commands have already been composed.
569   */
570  public void registerComposedCommands(Command... commands) {
571    var commandSet = Set.of(commands);
572    requireNotComposed(commandSet);
573    m_composedCommands.addAll(commandSet);
574  }
575
576  /**
577   * Clears the list of composed commands, allowing all commands to be freely used again.
578   *
579   * <p>WARNING: Using this haphazardly can result in unexpected/undesirable behavior. Do not use
580   * this unless you fully understand what you are doing.
581   */
582  public void clearComposedCommands() {
583    m_composedCommands.clear();
584  }
585
586  /**
587   * Removes a single command from the list of composed commands, allowing it to be freely used
588   * again.
589   *
590   * <p>WARNING: Using this haphazardly can result in unexpected/undesirable behavior. Do not use
591   * this unless you fully understand what you are doing.
592   *
593   * @param command the command to remove from the list of grouped commands
594   */
595  public void removeComposedCommand(Command command) {
596    m_composedCommands.remove(command);
597  }
598
599  /**
600   * Requires that the specified command hasn't been already added to a composition.
601   *
602   * @param command The command to check
603   * @throws IllegalArgumentException if the given commands have already been composed.
604   */
605  public void requireNotComposed(Command command) {
606    if (m_composedCommands.contains(command)) {
607      throw new IllegalArgumentException(
608          "Commands that have been composed may not be added to another composition or scheduled"
609              + "individually!");
610    }
611  }
612
613  /**
614   * Requires that the specified commands not have been already added to a composition.
615   *
616   * @param commands The commands to check
617   * @throws IllegalArgumentException if the given commands have already been composed.
618   */
619  public void requireNotComposed(Collection<Command> commands) {
620    if (!Collections.disjoint(commands, getComposedCommands())) {
621      throw new IllegalArgumentException(
622          "Commands that have been composed may not be added to another composition or scheduled"
623              + "individually!");
624    }
625  }
626
627  /**
628   * Check if the given command has been composed.
629   *
630   * @param command The command to check
631   * @return true if composed
632   * @throws IllegalArgumentException if the given commands have already been composed.
633   */
634  public boolean isComposed(Command command) {
635    return getComposedCommands().contains(command);
636  }
637
638  Set<Command> getComposedCommands() {
639    return m_composedCommands;
640  }
641
642  @Override
643  public void initSendable(NTSendableBuilder builder) {
644    builder.setSmartDashboardType("Scheduler");
645    final StringArrayPublisher namesPub = new StringArrayTopic(builder.getTopic("Names")).publish();
646    final IntegerArrayPublisher idsPub = new IntegerArrayTopic(builder.getTopic("Ids")).publish();
647    final IntegerArrayEntry cancelEntry =
648        new IntegerArrayTopic(builder.getTopic("Cancel")).getEntry(new long[] {});
649    builder.addCloseable(namesPub);
650    builder.addCloseable(idsPub);
651    builder.addCloseable(cancelEntry);
652    builder.setUpdateTable(
653        () -> {
654          if (namesPub == null || idsPub == null || cancelEntry == null) {
655            return;
656          }
657
658          Map<Long, Command> ids = new LinkedHashMap<>();
659          List<String> names = new ArrayList<>();
660          long[] ids2 = new long[m_scheduledCommands.size()];
661
662          int i = 0;
663          for (Command command : m_scheduledCommands) {
664            long id = command.hashCode();
665            ids.put(id, command);
666            names.add(command.getName());
667            ids2[i] = id;
668            i++;
669          }
670
671          long[] toCancel = cancelEntry.get();
672          if (toCancel.length > 0) {
673            for (long hash : toCancel) {
674              cancel(ids.get(hash));
675              ids.remove(hash);
676            }
677            cancelEntry.set(new long[] {});
678          }
679
680          namesPub.set(names.toArray(new String[] {}));
681          idsPub.set(ids2);
682        });
683  }
684}