WPILibC++ 2023.4.3
Subsystem.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <type_traits>
8#include <utility>
9
11
12namespace frc2 {
13class Command;
14class CommandPtr;
15/**
16 * A robot subsystem. Subsystems are the basic unit of robot organization in
17 * the Command-based framework; they encapsulate low-level hardware objects
18 * (motor controllers, sensors, etc) and provide methods through which they can
19 * be used by Commands. Subsystems are used by the CommandScheduler's resource
20 * management system to ensure multiple robot actions are not "fighting" over
21 * the same hardware; Commands that use a subsystem should include that
22 * subsystem in their GetRequirements() method, and resources used within a
23 * subsystem should generally remain encapsulated and not be shared by other
24 * parts of the robot.
25 *
26 * <p>Subsystems must be registered with the scheduler with the
27 * CommandScheduler.RegisterSubsystem() method in order for the
28 * Periodic() method to be called. It is recommended that this method be called
29 * from the constructor of users' Subsystem implementations. The
30 * SubsystemBase class offers a simple base for user implementations
31 * that handles this.
32 *
33 * This class is provided by the NewCommands VendorDep
34 *
35 * @see Command
36 * @see CommandScheduler
37 * @see SubsystemBase
38 */
39class Subsystem {
40 public:
41 virtual ~Subsystem();
42 /**
43 * This method is called periodically by the CommandScheduler. Useful for
44 * updating subsystem-specific state that you don't want to offload to a
45 * Command. Teams should try to be consistent within their own codebases
46 * about which responsibilities will be handled by Commands, and which will be
47 * handled here.
48 */
49 virtual void Periodic();
50
51 /**
52 * This method is called periodically by the CommandScheduler. Useful for
53 * updating subsystem-specific state that needs to be maintained for
54 * simulations, such as for updating simulation classes and setting simulated
55 * sensor readings.
56 */
57 virtual void SimulationPeriodic();
58
59 /**
60 * Sets the default Command of the subsystem. The default command will be
61 * automatically scheduled when no other commands are scheduled that require
62 * the subsystem. Default commands should generally not end on their own, i.e.
63 * their IsFinished() method should always return false. Will automatically
64 * register this subsystem with the CommandScheduler.
65 *
66 * @param defaultCommand the default command to associate with this subsystem
67 */
68 template <class T, typename = std::enable_if_t<std::is_base_of_v<
69 Command, std::remove_reference_t<T>>>>
70 void SetDefaultCommand(T&& defaultCommand) {
72 this, std::forward<T>(defaultCommand));
73 }
74
75 /**
76 * Sets the default Command of the subsystem. The default command will be
77 * automatically scheduled when no other commands are scheduled that require
78 * the subsystem. Default commands should generally not end on their own, i.e.
79 * their IsFinished() method should always return false. Will automatically
80 * register this subsystem with the CommandScheduler.
81 *
82 * @param defaultCommand the default command to associate with this subsystem
83 */
84 void SetDefaultCommand(CommandPtr&& defaultCommand);
85
86 /**
87 * Removes the default command for the subsystem. This will not cancel the
88 * default command if it is currently running.
89 */
91
92 /**
93 * Gets the default command for this subsystem. Returns null if no default
94 * command is currently associated with the subsystem.
95 *
96 * @return the default command associated with this subsystem
97 */
99
100 /**
101 * Returns the command currently running on this subsystem. Returns null if
102 * no command is currently scheduled that requires this subsystem.
103 *
104 * @return the scheduled command currently requiring this subsystem
105 */
107
108 /**
109 * Registers this subsystem with the CommandScheduler, allowing its
110 * Periodic() method to be called when the scheduler runs.
111 */
112 void Register();
113
114 /**
115 * Constructs a command that runs an action once and finishes. Requires this
116 * subsystem.
117 *
118 * @param action the action to run
119 */
120 [[nodiscard]] CommandPtr RunOnce(std::function<void()> action);
121
122 /**
123 * Constructs a command that runs an action every iteration until interrupted.
124 * Requires this subsystem.
125 *
126 * @param action the action to run
127 */
128 [[nodiscard]] CommandPtr Run(std::function<void()> action);
129
130 /**
131 * Constructs a command that runs an action once and another action when the
132 * command is interrupted. Requires this subsystem.
133 *
134 * @param start the action to run on start
135 * @param end the action to run on interrupt
136 */
137 [[nodiscard]] CommandPtr StartEnd(std::function<void()> start,
138 std::function<void()> end);
139
140 /**
141 * Constructs a command that runs an action every iteration until interrupted,
142 * and then runs a second action. Requires this subsystem.
143 *
144 * @param run the action to run every iteration
145 * @param end the action to run on interrupt
146 */
147 [[nodiscard]] CommandPtr RunEnd(std::function<void()> run,
148 std::function<void()> end);
149};
150} // namespace frc2
A state machine representing a complete action to be performed by the robot.
Definition: Command.h:47
A wrapper around std::unique_ptr<Command> so commands have move-only semantics.
Definition: CommandPtr.h:28
static CommandScheduler & GetInstance()
Returns the Scheduler instance.
void SetDefaultCommand(Subsystem *subsystem, T &&defaultCommand)
Sets the default command for a subsystem.
Definition: CommandScheduler.h:180
A robot subsystem.
Definition: Subsystem.h:39
void SetDefaultCommand(T &&defaultCommand)
Sets the default Command of the subsystem.
Definition: Subsystem.h:70
void SetDefaultCommand(CommandPtr &&defaultCommand)
Sets the default Command of the subsystem.
Command * GetCurrentCommand() const
Returns the command currently running on this subsystem.
void Register()
Registers this subsystem with the CommandScheduler, allowing its Periodic() method to be called when ...
virtual ~Subsystem()
CommandPtr RunOnce(std::function< void()> action)
Constructs a command that runs an action once and finishes.
CommandPtr RunEnd(std::function< void()> run, std::function< void()> end)
Constructs a command that runs an action every iteration until interrupted, and then runs a second ac...
void RemoveDefaultCommand()
Removes the default command for the subsystem.
virtual void SimulationPeriodic()
This method is called periodically by the CommandScheduler.
virtual void Periodic()
This method is called periodically by the CommandScheduler.
CommandPtr StartEnd(std::function< void()> start, std::function< void()> end)
Constructs a command that runs an action once and another action when the command is interrupted.
Command * GetDefaultCommand() const
Gets the default command for this subsystem.
CommandPtr Run(std::function< void()> action)
Constructs a command that runs an action every iteration until interrupted.
typename std::enable_if< B, T >::type enable_if_t
Definition: core.h:298
static EIGEN_DEPRECATED const end_t end
Definition: IndexedViewHelper.h:181
Definition: InstantCommand.h:14