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 */
022public interface Subsystem {
023  /**
024   * This method is called periodically by the {@link CommandScheduler}. Useful for updating
025   * subsystem-specific state that you don't want to offload to a {@link Command}. Teams should try
026   * to be consistent within their own codebases about which responsibilities will be handled by
027   * Commands, and which will be handled here.
028   */
029  default void periodic() {}
030
031  /**
032   * This method is called periodically by the {@link CommandScheduler}. Useful for updating
033   * subsystem-specific state that needs to be maintained for simulations, such as for updating
034   * {@link edu.wpi.first.wpilibj.simulation} classes and setting simulated sensor readings.
035   */
036  default void simulationPeriodic() {}
037
038  /**
039   * Sets the default {@link Command} of the subsystem. The default command will be automatically
040   * scheduled when no other commands are scheduled that require the subsystem. Default commands
041   * should generally not end on their own, i.e. their {@link Command#isFinished()} method should
042   * always return false. Will automatically register this subsystem with the {@link
043   * CommandScheduler}.
044   *
045   * @param defaultCommand the default command to associate with this subsystem
046   */
047  default void setDefaultCommand(Command defaultCommand) {
048    CommandScheduler.getInstance().setDefaultCommand(this, defaultCommand);
049  }
050
051  /**
052   * Gets the default command for this subsystem. Returns null if no default command is currently
053   * associated with the subsystem.
054   *
055   * @return the default command associated with this subsystem
056   */
057  default Command getDefaultCommand() {
058    return CommandScheduler.getInstance().getDefaultCommand(this);
059  }
060
061  /**
062   * Returns the command currently running on this subsystem. Returns null if no command is
063   * currently scheduled that requires this subsystem.
064   *
065   * @return the scheduled command currently requiring this subsystem
066   */
067  default Command getCurrentCommand() {
068    return CommandScheduler.getInstance().requiring(this);
069  }
070
071  /**
072   * Registers this subsystem with the {@link CommandScheduler}, allowing its {@link
073   * Subsystem#periodic()} method to be called when the scheduler runs.
074   */
075  default void register() {
076    CommandScheduler.getInstance().registerSubsystem(this);
077  }
078}