מערכות

Subsystems are the basic unit of robot organization in the command-based paradigm. A subsystem is an abstraction for a collection of robot hardware that operates together as a unit. Subsystems form an encapsulation for this hardware, ”hiding“ it from the rest of the robot code and restricting access to it except through the subsystem’s public methods. Restricting the access in this way provides a single convenient place for code that might otherwise be duplicated in multiple places (such as scaling motor outputs or checking limit switches) if the subsystem internals were exposed. It also allows changes to the specific details of how the subsystem works (the ”implementation“) to be isolated from the rest of robot code, making it far easier to make substantial changes if/when the design constraints change.

Subsystems also serve as the backbone of the CommandScheduler’s resource management system. Commands may declare resource requirements by specifying which subsystems they interact with; the scheduler will never concurrently schedule more than one command that requires a given subsystem. An attempt to schedule a command that requires a subsystem that is already-in-use will either interrupt the currently-running command or be ignored, based on the running command’s Interruption Behavior.

Subsystems can be associated with ”default commands“ that will be automatically scheduled when no other command is currently using the subsystem. This is useful for ”background“ actions such as controlling the robot drive, keeping an arm held at a setpoint, or stopping motors when the subsystem isn’t used. Similar functionality can be achieved in the subsystem’s periodic() method, which is run once per run of the scheduler; teams should try to be consistent within their codebase about which functionality is achieved through either of these methods. Subsystems are represented in the command-based library by the Subsystem interface (Java, C++, Python).

Creating a Subsystem

The recommended method to create a subsystem for most users is to subclass the abstract SubsystemBase class in (Java, C++), as seen in the command-based template (Java, C++). In Python, because Python does not have interfaces, the Subsystem class is a concrete class that can be subclassed directly (Python). The following example demonstrates how to create a simple subsystem in each of the supported languages:

 7import edu.wpi.first.wpilibj2.command.Command;
 8import edu.wpi.first.wpilibj2.command.SubsystemBase;
 9
10public class ExampleSubsystem extends SubsystemBase {
11  /** Creates a new ExampleSubsystem. */
12  public ExampleSubsystem() {}
13
14  /**
15   * Example command factory method.
16   *
17   * @return a command
18   */
19  public Command exampleMethodCommand() {
20    // Inline construction of command goes here.
21    // Subsystem::RunOnce implicitly requires `this` subsystem.
22    return runOnce(
23        () -> {
24          /* one-time action goes here */
25        });
26  }
27
28  /**
29   * An example method querying a boolean state of the subsystem (for example, a digital sensor).
30   *
31   * @return value of some boolean subsystem state, such as a digital sensor.
32   */
33  public boolean exampleCondition() {
34    // Query some boolean state, such as a digital sensor.
35    return false;
36  }
37
38  @Override
39  public void periodic() {
40    // This method will be called once per scheduler run
41  }
42
43  @Override
44  public void simulationPeriodic() {
45    // This method will be called once per scheduler run during simulation
46  }
47}
 5#pragma once
 6
 7#include <frc2/command/CommandPtr.h>
 8#include <frc2/command/SubsystemBase.h>
 9
10class ExampleSubsystem : public frc2::SubsystemBase {
11 public:
12  ExampleSubsystem();
13
14  /**
15   * Example command factory method.
16   */
17  frc2::CommandPtr ExampleMethodCommand();
18
19  /**
20   * An example method querying a boolean state of the subsystem (for example, a
21   * digital sensor).
22   *
23   * @return value of some boolean subsystem state, such as a digital sensor.
24   */
25  bool ExampleCondition();
26
27  /**
28   * Will be called periodically whenever the CommandScheduler runs.
29   */
30  void Periodic() override;
31
32  /**
33   * Will be called periodically whenever the CommandScheduler runs during
34   * simulation.
35   */
36  void SimulationPeriodic() override;
37
38 private:
39  // Components (e.g. motor controllers and sensors) should generally be
40  // declared private and exposed only through public methods.
41};
from commands2 import Command
from commands2 import Subsystem
class ExampleSubsystem(Subsystem):
    def __init__(self):
        """Creates a new ExampleSubsystem."""
        super().__init__()
    def exampleMethodCommand()->Command:
        """
        Example command factory method.
         :return a command
        """
        return self.runOnce(
            lambda: # one-time action goes here #
        )
    def exampleCondition(self)->bool:
        """
        An example method querying a boolean state of the subsystem (for example, a digital sensor).
        :return value of some boolean subsystem state, such as a digital sensor.
        """
        #Query some boolean state, such as a digital sensor.
        return False
    def periodic(self):
        # This method will be called once per scheduler run
        pass
    def simulationPeriodic(self):
        # This method will be called once per scheduler run during simulation
        pass

This class contains a few convenience features on top of the basic Subsystem interface: it automatically calls the register() method in its constructor to register the subsystem with the scheduler (this is necessary for the periodic() method to be called when the scheduler runs), and also implements the Sendable interface so that it can be sent to the dashboard to display/log relevant status information.

Advanced users seeking more flexibility may simply create a class that implements the Subsystem interface.

Simple Subsystem Example

What might a functional subsystem look like in practice? Below is a simple pneumatically-actuated hatch mechanism from the HatchBotTraditional example project (Java, C++, Python):

 5package edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems;
 6
 7import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kForward;
 8import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kReverse;
 9
10import edu.wpi.first.util.sendable.SendableBuilder;
11import edu.wpi.first.wpilibj.DoubleSolenoid;
12import edu.wpi.first.wpilibj.PneumaticsModuleType;
13import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.HatchConstants;
14import edu.wpi.first.wpilibj2.command.SubsystemBase;
15
16/** A hatch mechanism actuated by a single {@link DoubleSolenoid}. */
17public class HatchSubsystem extends SubsystemBase {
18  private final DoubleSolenoid m_hatchSolenoid =
19      new DoubleSolenoid(
20          PneumaticsModuleType.CTREPCM,
21          HatchConstants.kHatchSolenoidPorts[0],
22          HatchConstants.kHatchSolenoidPorts[1]);
23
24  /** Grabs the hatch. */
25  public void grabHatch() {
26    m_hatchSolenoid.set(kForward);
27  }
28
29  /** Releases the hatch. */
30  public void releaseHatch() {
31    m_hatchSolenoid.set(kReverse);
32  }
33
34  @Override
35  public void initSendable(SendableBuilder builder) {
36    super.initSendable(builder);
37    // Publish the solenoid state to telemetry.
38    builder.addBooleanProperty("extended", () -> m_hatchSolenoid.get() == kForward, null);
39  }
40}
 5#pragma once
 6
 7#include <frc/DoubleSolenoid.h>
 8#include <frc/PneumaticsControlModule.h>
 9#include <frc2/command/SubsystemBase.h>
10
11#include "Constants.h"
12
13class HatchSubsystem : public frc2::SubsystemBase {
14 public:
15  HatchSubsystem();
16
17  // Subsystem methods go here.
18
19  /**
20   * Grabs the hatch.
21   */
22  void GrabHatch();
23
24  /**
25   * Releases the hatch.
26   */
27  void ReleaseHatch();
28
29  void InitSendable(wpi::SendableBuilder& builder) override;
30
31 private:
32  // Components (e.g. motor controllers and sensors) should generally be
33  // declared private and exposed only through public methods.
34  frc::DoubleSolenoid m_hatchSolenoid;
35};
 5#include "subsystems/HatchSubsystem.h"
 6
 7#include <wpi/sendable/SendableBuilder.h>
 8
 9using namespace HatchConstants;
10
11HatchSubsystem::HatchSubsystem()
12    : m_hatchSolenoid{frc::PneumaticsModuleType::CTREPCM,
13                      kHatchSolenoidPorts[0], kHatchSolenoidPorts[1]} {}
14
15void HatchSubsystem::GrabHatch() {
16  m_hatchSolenoid.Set(frc::DoubleSolenoid::kForward);
17}
18
19void HatchSubsystem::ReleaseHatch() {
20  m_hatchSolenoid.Set(frc::DoubleSolenoid::kReverse);
21}
22
23void HatchSubsystem::InitSendable(wpi::SendableBuilder& builder) {
24  SubsystemBase::InitSendable(builder);
25
26  // Publish the solenoid state to telemetry.
27  builder.AddBooleanProperty(
28      "extended",
29      [this] { return m_hatchSolenoid.Get() == frc::DoubleSolenoid::kForward; },
30      nullptr);
31}
 7import wpilib
 8import commands2
 9
10import constants
11
12
13class HatchSubsystem(commands2.Subsystem):
14    def __init__(self) -> None:
15        super().__init__()
16
17        self.hatchSolenoid = wpilib.DoubleSolenoid(
18            constants.kHatchSolenoidModule,
19            constants.kHatchSolenoidModuleType,
20            *constants.kHatchSolenoidPorts
21        )
22
23    def grabHatch(self) -> None:
24        """Grabs the hatch"""
25        self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.kForward)
26
27    def releaseHatch(self) -> None:
28        """Releases the hatch"""
29        self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.kReverse)

Notice that the subsystem hides the presence of the DoubleSolenoid from outside code (it is declared private), and instead publicly exposes two higher-level, descriptive robot actions: grabHatch() and releaseHatch(). It is extremely important that ”implementation details“ such as the double solenoid be ”hidden“ in this manner; this ensures that code outside the subsystem will never cause the solenoid to be in an unexpected state. It also allows the user to change the implementation (for instance, a motor could be used instead of a pneumatic) without any of the code outside of the subsystem having to change with it.

Alternatively, instead of writing void public methods that are called from commands, we can define the public methods as factories that return a command. Consider the following from the HatchBotInlined example project (Java, C++, Python):

 5package edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems;
 6
 7import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kForward;
 8import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kReverse;
 9
10import edu.wpi.first.util.sendable.SendableBuilder;
11import edu.wpi.first.wpilibj.DoubleSolenoid;
12import edu.wpi.first.wpilibj.PneumaticsModuleType;
13import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.HatchConstants;
14import edu.wpi.first.wpilibj2.command.Command;
15import edu.wpi.first.wpilibj2.command.SubsystemBase;
16
17/** A hatch mechanism actuated by a single {@link edu.wpi.first.wpilibj.DoubleSolenoid}. */
18public class HatchSubsystem extends SubsystemBase {
19  private final DoubleSolenoid m_hatchSolenoid =
20      new DoubleSolenoid(
21          PneumaticsModuleType.CTREPCM,
22          HatchConstants.kHatchSolenoidPorts[0],
23          HatchConstants.kHatchSolenoidPorts[1]);
24
25  /** Grabs the hatch. */
26  public Command grabHatchCommand() {
27    // implicitly require `this`
28    return this.runOnce(() -> m_hatchSolenoid.set(kForward));
29  }
30
31  /** Releases the hatch. */
32  public Command releaseHatchCommand() {
33    // implicitly require `this`
34    return this.runOnce(() -> m_hatchSolenoid.set(kReverse));
35  }
36
37  @Override
38  public void initSendable(SendableBuilder builder) {
39    super.initSendable(builder);
40    // Publish the solenoid state to telemetry.
41    builder.addBooleanProperty("extended", () -> m_hatchSolenoid.get() == kForward, null);
42  }
43}
 5#pragma once
 6
 7#include <frc/DoubleSolenoid.h>
 8#include <frc/PneumaticsControlModule.h>
 9#include <frc2/command/CommandPtr.h>
10#include <frc2/command/SubsystemBase.h>
11
12#include "Constants.h"
13
14class HatchSubsystem : public frc2::SubsystemBase {
15 public:
16  HatchSubsystem();
17
18  // Subsystem methods go here.
19
20  /**
21   * Grabs the hatch.
22   */
23  frc2::CommandPtr GrabHatchCommand();
24
25  /**
26   * Releases the hatch.
27   */
28  frc2::CommandPtr ReleaseHatchCommand();
29
30  void InitSendable(wpi::SendableBuilder& builder) override;
31
32 private:
33  // Components (e.g. motor controllers and sensors) should generally be
34  // declared private and exposed only through public methods.
35  frc::DoubleSolenoid m_hatchSolenoid;
36};
 5#include "subsystems/HatchSubsystem.h"
 6
 7#include <wpi/sendable/SendableBuilder.h>
 8
 9using namespace HatchConstants;
10
11HatchSubsystem::HatchSubsystem()
12    : m_hatchSolenoid{frc::PneumaticsModuleType::CTREPCM,
13                      kHatchSolenoidPorts[0], kHatchSolenoidPorts[1]} {}
14
15frc2::CommandPtr HatchSubsystem::GrabHatchCommand() {
16  // implicitly require `this`
17  return this->RunOnce(
18      [this] { m_hatchSolenoid.Set(frc::DoubleSolenoid::kForward); });
19}
20
21frc2::CommandPtr HatchSubsystem::ReleaseHatchCommand() {
22  // implicitly require `this`
23  return this->RunOnce(
24      [this] { m_hatchSolenoid.Set(frc::DoubleSolenoid::kReverse); });
25}
26
27void HatchSubsystem::InitSendable(wpi::SendableBuilder& builder) {
28  SubsystemBase::InitSendable(builder);
29
30  // Publish the solenoid state to telemetry.
31  builder.AddBooleanProperty(
32      "extended",
33      [this] { return m_hatchSolenoid.Get() == frc::DoubleSolenoid::kForward; },
34      nullptr);
35}
 7import wpilib
 8import commands2
 9import commands2.cmd
10
11import constants
12
13
14class HatchSubsystem(commands2.Subsystem):
15    def __init__(self) -> None:
16        super().__init__()
17
18        self.hatchSolenoid = wpilib.DoubleSolenoid(
19            constants.kHatchSolenoidModule,
20            constants.kHatchSolenoidModuleType,
21            *constants.kHatchSolenoidPorts
22        )
23
24    def grabHatch(self) -> commands2.Command:
25        """Grabs the hatch"""
26        return commands2.cmd.runOnce(
27            lambda: self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.kForward), self
28        )
29
30    def releaseHatch(self) -> commands2.Command:
31        """Releases the hatch"""
32        return commands2.cmd.runOnce(
33            lambda: self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.kReverse), self
34        )

Note the qualification of the RunOnce factory used here: this isn’t the static factory in Commands! Subsystems have similar instance factories that return commands requiring this (Java/C++) or self (Python) subsystem. Here, the Subsystem.runOnce(Runnable) factory (Java, C++, Python) is used.

For a comparison between these options, see Instance Command Factory Methods.

Periodic

Subsystems have a periodic method that is called once every scheduler iteration (usually, once every 20 ms). This method is typically used for telemetry and other periodic actions that do not interfere with whatever command is requiring the subsystem.

117  @Override
118  public void periodic() {
119    // Update the odometry in the periodic block
120    m_odometry.update(
121        Rotation2d.fromDegrees(getHeading()),
122        m_leftEncoder.getDistance(),
123        m_rightEncoder.getDistance());
124    m_fieldSim.setRobotPose(getPose());
125  }
30  void Periodic() override;
30void DriveSubsystem::Periodic() {
31  // Implementation of subsystem periodic method goes here.
32  m_odometry.Update(m_gyro.GetRotation2d(),
33                    units::meter_t{m_leftEncoder.GetDistance()},
34                    units::meter_t{m_rightEncoder.GetDistance()});
35  m_fieldSim.SetRobotPose(m_odometry.GetPose());
36}
def periodic(self):
    #Update the odometry in the periodic block
    self.odometry.update(
        Rotation2d.fromDegrees(getHeading()),
        self.leftEncoder.getDistance(),
        self.rightEncoder.getDistance())
    self.fieldSim.setRobotPose(getPose())

There is also a simulationPeriodic() method that is similar to periodic() except that it is only run during Simulation and can be used to update the state of the robot.

Default Commands

הערה

In the C++ command-based library, the CommandScheduler owns the default command object.

”Default commands“ are commands that run automatically whenever a subsystem is not being used by another command. This can be useful for ”background“ actions such as controlling the robot drive, or keeping an arm held at a setpoint.

Setting a default command for a subsystem is very easy; one simply calls CommandScheduler.getInstance().setDefaultCommand(), or, more simply, the setDefaultCommand() method of the Subsystem interface:

CommandScheduler.getInstance().setDefaultCommand(exampleSubsystem, exampleCommand);
CommandScheduler.GetInstance().SetDefaultCommand(exampleSubsystem, std::move(exampleCommand));
CommandScheduler.getInstance().setDefaultCommand(exampleSubsystem, exampleCommand)
exampleSubsystem.setDefaultCommand(exampleCommand);
exampleSubsystem.SetDefaultCommand(std::move(exampleCommand));
exampleSubsystem.setDefaultCommand(exampleCommand)

הערה

A command that is assigned as the default command for a subsystem must require that subsystem.