WPILibC++ 2023.4.3
frc2::Subsystem Class Reference

A robot subsystem. More...

#include <frc2/command/Subsystem.h>

Inheritance diagram for frc2::Subsystem:
frc2::SubsystemBase frc2::PIDSubsystem frc2::ProfiledPIDSubsystem< Distance > frc2::TrapezoidProfileSubsystem< Distance >

Public Member Functions

virtual ~Subsystem ()
 
virtual void Periodic ()
 This method is called periodically by the CommandScheduler. More...
 
virtual void SimulationPeriodic ()
 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...
 
void SetDefaultCommand (CommandPtr &&defaultCommand)
 Sets the default Command of the subsystem. More...
 
void RemoveDefaultCommand ()
 Removes the default command for the subsystem. More...
 
CommandGetDefaultCommand () const
 Gets the default command for this subsystem. More...
 
CommandGetCurrentCommand () 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. More...
 
CommandPtr RunOnce (std::function< void()> action)
 Constructs a command that runs an action once and finishes. More...
 
CommandPtr Run (std::function< void()> action)
 Constructs a command that runs an action every iteration until interrupted. More...
 
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. More...
 
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 action. More...
 

Detailed Description

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.

This class is provided by the NewCommands VendorDep

See also
Command
CommandScheduler
SubsystemBase

Constructor & Destructor Documentation

◆ ~Subsystem()

virtual frc2::Subsystem::~Subsystem ( )
virtual

Member Function Documentation

◆ GetCurrentCommand()

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.

Returns
the scheduled command currently requiring this subsystem

◆ GetDefaultCommand()

Command * frc2::Subsystem::GetDefaultCommand ( ) const

Gets the default command for this subsystem.

Returns null if no default command is currently associated with the subsystem.

Returns
the default command associated with this subsystem

◆ Periodic()

virtual void frc2::Subsystem::Periodic ( )
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::PIDSubsystem, frc2::ProfiledPIDSubsystem< Distance >, and frc2::TrapezoidProfileSubsystem< Distance >.

◆ Register()

void frc2::Subsystem::Register ( )

Registers this subsystem with the CommandScheduler, allowing its Periodic() method to be called when the scheduler runs.

◆ RemoveDefaultCommand()

void frc2::Subsystem::RemoveDefaultCommand ( )

Removes the default command for the subsystem.

This will not cancel the default command if it is currently running.

◆ Run()

CommandPtr frc2::Subsystem::Run ( std::function< void()>  action)

Constructs a command that runs an action every iteration until interrupted.

Requires this subsystem.

Parameters
actionthe action to run

◆ RunEnd()

CommandPtr frc2::Subsystem::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 action.

Requires this subsystem.

Parameters
runthe action to run every iteration
endthe action to run on interrupt

◆ RunOnce()

CommandPtr frc2::Subsystem::RunOnce ( std::function< void()>  action)

Constructs a command that runs an action once and finishes.

Requires this subsystem.

Parameters
actionthe action to run

◆ SetDefaultCommand() [1/2]

void frc2::Subsystem::SetDefaultCommand ( CommandPtr &&  defaultCommand)

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.

Parameters
defaultCommandthe default command to associate with this subsystem

◆ SetDefaultCommand() [2/2]

template<class T , typename = std::enable_if_t<std::is_base_of_v< Command, std::remove_reference_t<T>>>>
void frc2::Subsystem::SetDefaultCommand ( T &&  defaultCommand)
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.

Parameters
defaultCommandthe default command to associate with this subsystem

◆ SimulationPeriodic()

virtual void frc2::Subsystem::SimulationPeriodic ( )
virtual

This method is called periodically by the CommandScheduler.

Useful for updating subsystem-specific state that needs to be maintained for simulations, such as for updating simulation classes and setting simulated sensor readings.

◆ StartEnd()

CommandPtr frc2::Subsystem::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.

Requires this subsystem.

Parameters
startthe action to run on start
endthe action to run on interrupt

The documentation for this class was generated from the following file: