|
WPILibC++
2020.3.2
|
A robot subsystem. More...
#include <Subsystem.h>
Public Member Functions | |
| virtual void | Periodic () |
| This method is called periodically by the CommandScheduler. More... | |
| template<class T , typename = std::enable_if_t<std::is_base_of_v< Command, std::remove_reference_t<T>>>> | |
| void | SetDefaultCommand (T &&defaultCommand) |
| Sets the default Command of the subsystem. More... | |
| Command * | GetDefaultCommand () const |
| Gets the default command for this subsystem. More... | |
| Command * | GetCurrentCommand () const |
| Returns the command currently running on this subsystem. More... | |
| void | Register () |
| Registers this subsystem with the CommandScheduler, allowing its Periodic() method to be called when the scheduler runs. | |
A robot subsystem.
Subsystems are the basic unit of robot organization in the Command-based framework; they encapsulate low-level hardware objects (motor controllers, sensors, etc) and provide methods through which they can be used by Commands. Subsystems are used by the CommandScheduler's resource management system to ensure multiple robot actions are not "fighting" over the same hardware; Commands that use a subsystem should include that subsystem in their GetRequirements() method, and resources used within a subsystem should generally remain encapsulated and not be shared by other parts of the robot.
Subsystems must be registered with the scheduler with the CommandScheduler.RegisterSubsystem() method in order for the Periodic() method to be called. It is recommended that this method be called from the constructor of users' Subsystem implementations. The SubsystemBase class offers a simple base for user implementations that handles this.
| Command* frc2::Subsystem::GetCurrentCommand | ( | ) | const |
Returns the command currently running on this subsystem.
Returns null if no command is currently scheduled that requires this subsystem.
| Command* frc2::Subsystem::GetDefaultCommand | ( | ) | const |
Gets the default command for this subsystem.
Returns null if no default command is currently associated with the subsystem.
|
virtual |
This method is called periodically by the CommandScheduler.
Useful for updating subsystem-specific state that you don't want to offload to a Command. Teams should try to be consistent within their own codebases about which responsibilities will be handled by Commands, and which will be handled here.
Reimplemented in frc2::TrapezoidProfileSubsystem< Distance >, frc2::ProfiledPIDSubsystem< Distance >, and frc2::PIDSubsystem.
|
inline |
Sets the default Command of the subsystem.
The default command will be automatically scheduled when no other commands are scheduled that require the subsystem. Default commands should generally not end on their own, i.e. their IsFinished() method should always return false. Will automatically register this subsystem with the CommandScheduler.
| defaultCommand | the default command to associate with this subsystem |