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
007/**
008 * A robot subsystem. Subsystems are the basic unit of robot organization in the Command-based
009 * framework; they encapsulate low-level hardware objects (motor controllers, sensors, etc.) and
010 * provide methods through which they can be used by {@link Command}s. Subsystems are used by the
011 * {@link CommandScheduler}'s resource management system to ensure multiple robot actions are not
012 * "fighting" over the same hardware; Commands that use a subsystem should include that subsystem in
013 * their {@link Command#getRequirements()} method, and resources used within a subsystem should
014 * generally remain encapsulated and not be shared by other parts of the robot.
015 *
016 * <p>Subsystems must be registered with the scheduler with the {@link
017 * CommandScheduler#registerSubsystem(Subsystem...)} method in order for the {@link
018 * Subsystem#periodic()} method to be called. It is recommended that this method be called from the
019 * constructor of users' Subsystem implementations. The {@link SubsystemBase} class offers a simple
020 * base for user implementations that handles this.
021 *
022 * <p>This class is provided by the NewCommands VendorDep
023 */
024public interface Subsystem {
025  /**
026   * This method is called periodically by the {@link CommandScheduler}. Useful for updating
027   * subsystem-specific state that you don't want to offload to a {@link Command}. Teams should try
028   * to be consistent within their own codebases about which responsibilities will be handled by
029   * Commands, and which will be handled here.
030   */
031  default void periodic() {}
032
033  /**
034   * This method is called periodically by the {@link CommandScheduler}. Useful for updating
035   * subsystem-specific state that needs to be maintained for simulations, such as for updating
036   * {@link edu.wpi.first.wpilibj.simulation} classes and setting simulated sensor readings.
037   */
038  default void simulationPeriodic() {}
039
040  /**
041   * Sets the default {@link Command} of the subsystem. The default command will be automatically
042   * scheduled when no other commands are scheduled that require the subsystem. Default commands
043   * should generally not end on their own, i.e. their {@link Command#isFinished()} method should
044   * always return false. Will automatically register this subsystem with the {@link
045   * CommandScheduler}.
046   *
047   * @param defaultCommand the default command to associate with this subsystem
048   */
049  default void setDefaultCommand(Command defaultCommand) {
050    CommandScheduler.getInstance().setDefaultCommand(this, defaultCommand);
051  }
052
053  /**
054   * Removes the default command for the subsystem. This will not cancel the default command if it
055   * is currently running.
056   */
057  default void removeDefaultCommand() {
058    CommandScheduler.getInstance().removeDefaultCommand(this);
059  }
060
061  /**
062   * Gets the default command for this subsystem. Returns null if no default command is currently
063   * associated with the subsystem.
064   *
065   * @return the default command associated with this subsystem
066   */
067  default Command getDefaultCommand() {
068    return CommandScheduler.getInstance().getDefaultCommand(this);
069  }
070
071  /**
072   * Returns the command currently running on this subsystem. Returns null if no command is
073   * currently scheduled that requires this subsystem.
074   *
075   * @return the scheduled command currently requiring this subsystem
076   */
077  default Command getCurrentCommand() {
078    return CommandScheduler.getInstance().requiring(this);
079  }
080
081  /**
082   * Registers this subsystem with the {@link CommandScheduler}, allowing its {@link
083   * Subsystem#periodic()} method to be called when the scheduler runs.
084   */
085  default void register() {
086    CommandScheduler.getInstance().registerSubsystem(this);
087  }
088
089  /**
090   * Constructs a command that runs an action once and finishes. Requires this subsystem.
091   *
092   * @param action the action to run
093   * @return the command
094   * @see InstantCommand
095   */
096  default CommandBase runOnce(Runnable action) {
097    return Commands.runOnce(action, this);
098  }
099
100  /**
101   * Constructs a command that runs an action every iteration until interrupted. Requires this
102   * subsystem.
103   *
104   * @param action the action to run
105   * @return the command
106   * @see RunCommand
107   */
108  default CommandBase run(Runnable action) {
109    return Commands.run(action, this);
110  }
111
112  /**
113   * Constructs a command that runs an action once and another action when the command is
114   * interrupted. Requires this subsystem.
115   *
116   * @param start the action to run on start
117   * @param end the action to run on interrupt
118   * @return the command
119   * @see StartEndCommand
120   */
121  default CommandBase startEnd(Runnable start, Runnable end) {
122    return Commands.startEnd(start, end, this);
123  }
124
125  /**
126   * Constructs a command that runs an action every iteration until interrupted, and then runs a
127   * second action. Requires this subsystem.
128   *
129   * @param run the action to run every iteration
130   * @param end the action to run on interrupt
131   * @return the command
132   */
133  default CommandBase runEnd(Runnable run, Runnable end) {
134    return Commands.runEnd(run, end, this);
135  }
136}