WPILibC++ 2023.4.3
frc2::RamseteCommand Class Reference

A command that uses a RAMSETE controller to follow a trajectory with a differential drive. More...

#include <frc2/command/RamseteCommand.h>

Inheritance diagram for frc2::RamseteCommand:
frc2::CommandHelper< CommandBase, RamseteCommand > frc2::CommandBase frc2::Command wpi::Sendable wpi::SendableHelper< CommandBase >

Public Member Functions

 RamseteCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::RamseteController controller, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::DifferentialDriveKinematics kinematics, std::function< frc::DifferentialDriveWheelSpeeds()> wheelSpeeds, frc2::PIDController leftController, frc2::PIDController rightController, std::function< void(units::volt_t, units::volt_t)> output, std::initializer_list< Subsystem * > requirements)
 Constructs a new RamseteCommand that, when executed, will follow the provided trajectory. More...
 
 RamseteCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::RamseteController controller, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::DifferentialDriveKinematics kinematics, std::function< frc::DifferentialDriveWheelSpeeds()> wheelSpeeds, frc2::PIDController leftController, frc2::PIDController rightController, std::function< void(units::volt_t, units::volt_t)> output, std::span< Subsystem *const > requirements={})
 Constructs a new RamseteCommand that, when executed, will follow the provided trajectory. More...
 
 RamseteCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::RamseteController controller, frc::DifferentialDriveKinematics kinematics, std::function< void(units::meters_per_second_t, units::meters_per_second_t)> output, std::initializer_list< Subsystem * > requirements)
 Constructs a new RamseteCommand that, when executed, will follow the provided trajectory. More...
 
 RamseteCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::RamseteController controller, frc::DifferentialDriveKinematics kinematics, std::function< void(units::meters_per_second_t, units::meters_per_second_t)> output, std::span< Subsystem *const > requirements={})
 Constructs a new RamseteCommand that, when executed, will follow the provided trajectory. More...
 
void Initialize () override
 The initial subroutine of a command. More...
 
void Execute () override
 The main body of a command. More...
 
void End (bool interrupted) override
 The action to take when the command ends. More...
 
bool IsFinished () override
 Whether the command has finished. More...
 
void InitSendable (wpi::SendableBuilder &builder) override
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from frc2::CommandHelper< CommandBase, RamseteCommand >
 CommandHelper ()=default
 
CommandPtr ToPtr () &&override
 
- Public Member Functions inherited from frc2::CommandBase
void AddRequirements (std::initializer_list< Subsystem * > requirements)
 Adds the specified Subsystem requirements to the command. More...
 
void AddRequirements (std::span< Subsystem *const > requirements)
 Adds the specified Subsystem requirements to the command. More...
 
void AddRequirements (wpi::SmallSet< Subsystem *, 4 > requirements)
 Adds the specified Subsystem requirements to the command. More...
 
void AddRequirements (Subsystem *requirement)
 Adds the specified Subsystem requirement to the command. More...
 
wpi::SmallSet< Subsystem *, 4 > GetRequirements () const override
 Gets the Subsystem requirements of the command. More...
 
void SetName (std::string_view name) override
 Sets the name of this Command. More...
 
std::string GetName () const override
 Gets the name of this Command. More...
 
std::string GetSubsystem () const
 Gets the subsystem name of this Command. More...
 
void SetSubsystem (std::string_view subsystem)
 Sets the subsystem name of this Command. More...
 
void InitSendable (wpi::SendableBuilder &builder) override
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from frc2::Command
 Command ()=default
 
virtual ~Command ()
 
 Command (const Command &)=default
 
Commandoperator= (const Command &rhs)
 
 Command (Command &&)=default
 
Commandoperator= (Command &&)=default
 
virtual void Initialize ()
 The initial subroutine of a command. More...
 
virtual void Execute ()
 The main body of a command. More...
 
virtual void End (bool interrupted)
 The action to take when the command ends. More...
 
virtual bool IsFinished ()
 Whether the command has finished. More...
 
virtual wpi::SmallSet< Subsystem *, 4 > GetRequirements () const =0
 Specifies the set of subsystems used by this command. More...
 
CommandPtr WithTimeout (units::second_t duration) &&
 Decorates this command with a timeout. More...
 
CommandPtr Until (std::function< bool()> condition) &&
 Decorates this command with an interrupt condition. More...
 
CommandPtr WithInterrupt (std::function< bool()> condition) &&
 Decorates this command with an interrupt condition. More...
 
CommandPtr BeforeStarting (std::function< void()> toRun, std::initializer_list< Subsystem * > requirements) &&
 Decorates this command with a runnable to run before this command starts. More...
 
CommandPtr BeforeStarting (std::function< void()> toRun, std::span< Subsystem *const > requirements={}) &&
 Decorates this command with a runnable to run before this command starts. More...
 
CommandPtr AndThen (std::function< void()> toRun, std::initializer_list< Subsystem * > requirements) &&
 Decorates this command with a runnable to run after the command finishes. More...
 
CommandPtr AndThen (std::function< void()> toRun, std::span< Subsystem *const > requirements={}) &&
 Decorates this command with a runnable to run after the command finishes. More...
 
PerpetualCommand Perpetually () &&
 
CommandPtr Repeatedly () &&
 Decorates this command to run repeatedly, restarting it when it ends, until this command is interrupted. More...
 
CommandPtr AsProxy () &&
 Decorates this command to run "by proxy" by wrapping it in a ProxyCommand. More...
 
CommandPtr Unless (std::function< bool()> condition) &&
 Decorates this command to only run if this condition is not met. More...
 
CommandPtr IgnoringDisable (bool doesRunWhenDisabled) &&
 Decorates this command to run or stop when disabled. More...
 
CommandPtr WithInterruptBehavior (Command::InterruptionBehavior interruptBehavior) &&
 Decorates this command to run or stop when disabled. More...
 
CommandPtr FinallyDo (std::function< void(bool)> end) &&
 Decorates this command with a lambda to call on interrupt or end, following the command's inherent Command::End(bool) method. More...
 
CommandPtr HandleInterrupt (std::function< void()> handler) &&
 Decorates this command with a lambda to call on interrupt, following the command's inherent Command::End(bool) method. More...
 
CommandPtr WithName (std::string_view name) &&
 Decorates this Command with a name. More...
 
void Schedule ()
 Schedules this command. More...
 
void Cancel ()
 Cancels this command. More...
 
bool IsScheduled () const
 Whether or not the command is currently scheduled. More...
 
bool HasRequirement (Subsystem *requirement) const
 Whether the command requires a given subsystem. More...
 
bool IsComposed () const
 Whether the command is currently grouped in a command group. More...
 
void SetComposed (bool isComposed)
 Sets whether the command is currently composed in a command composition. More...
 
bool IsGrouped () const
 Whether the command is currently grouped in a command group. More...
 
void SetGrouped (bool grouped)
 Sets whether the command is currently grouped in a command group. More...
 
virtual bool RunsWhenDisabled () const
 Whether the given command should run when the robot is disabled. More...
 
virtual InterruptionBehavior GetInterruptionBehavior () const
 How the command behaves when another command with a shared requirement is scheduled. More...
 
virtual std::string GetName () const
 Gets the name of this Command. More...
 
virtual void SetName (std::string_view name)
 Sets the name of this Command. More...
 
virtual CommandPtr ToPtr () &&=0
 Transfers ownership of this command to a unique pointer. More...
 
- Public Member Functions inherited from wpi::Sendable
virtual ~Sendable ()=default
 
virtual void InitSendable (SendableBuilder &builder)=0
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from wpi::SendableHelper< CommandBase >
 SendableHelper (const SendableHelper &rhs)=default
 
 SendableHelper (SendableHelper &&rhs)
 
SendableHelperoperator= (const SendableHelper &rhs)=default
 
SendableHelperoperator= (SendableHelper &&rhs)
 

Additional Inherited Members

- Public Types inherited from frc2::Command
enum class  InterruptionBehavior { kCancelSelf , kCancelIncoming }
 An enum describing the command's behavior when another command with a shared requirement is scheduled. More...
 
- Protected Member Functions inherited from frc2::CommandHelper< CommandBase, RamseteCommand >
std::unique_ptr< CommandTransferOwnership () &&override
 
- Protected Member Functions inherited from frc2::CommandBase
 CommandBase ()
 
virtual std::unique_ptr< CommandTransferOwnership () &&=0
 Transfers ownership of this command to a unique pointer. More...
 
- Protected Member Functions inherited from wpi::SendableHelper< CommandBase >
 SendableHelper ()=default
 
 ~SendableHelper ()
 
- Protected Attributes inherited from frc2::CommandBase
wpi::SmallSet< Subsystem *, 4 > m_requirements
 
- Protected Attributes inherited from frc2::Command
bool m_isComposed = false
 

Detailed Description

A command that uses a RAMSETE controller to follow a trajectory with a differential drive.

The command handles trajectory-following, PID calculations, and feedforwards internally. This is intended to be a more-or-less "complete solution" that can be used by teams without a great deal of controls expertise.

Advanced teams seeking more flexibility (for example, those who wish to use the onboard PID functionality of a "smart" motor controller) may use the secondary constructor that omits the PID and feedforward functionality, returning only the raw wheel speeds from the RAMSETE controller.

This class is provided by the NewCommands VendorDep

See also
RamseteController
Trajectory

Constructor & Destructor Documentation

◆ RamseteCommand() [1/4]

frc2::RamseteCommand::RamseteCommand ( frc::Trajectory  trajectory,
std::function< frc::Pose2d()>  pose,
frc::RamseteController  controller,
frc::SimpleMotorFeedforward< units::meters >  feedforward,
frc::DifferentialDriveKinematics  kinematics,
std::function< frc::DifferentialDriveWheelSpeeds()>  wheelSpeeds,
frc2::PIDController  leftController,
frc2::PIDController  rightController,
std::function< void(units::volt_t, units::volt_t)>  output,
std::initializer_list< Subsystem * >  requirements 
)

Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.

PID control and feedforward are handled internally, and outputs are scaled -12 to 12 representing units of volts.

Note: The controller will not set the outputVolts to zero upon completion of the path - this is left to the user, since it is not appropriate for paths with nonstationary endstates.

Parameters
trajectoryThe trajectory to follow.
poseA function that supplies the robot pose - use one of the odometry classes to provide this.
controllerThe RAMSETE controller used to follow the trajectory.
feedforwardA component for calculating the feedforward for the drive.
kinematicsThe kinematics for the robot drivetrain.
wheelSpeedsA function that supplies the speeds of the left and right sides of the robot drive.
leftControllerThe PIDController for the left side of the robot drive.
rightControllerThe PIDController for the right side of the robot drive.
outputA function that consumes the computed left and right outputs (in volts) for the robot drive.
requirementsThe subsystems to require.

◆ RamseteCommand() [2/4]

frc2::RamseteCommand::RamseteCommand ( frc::Trajectory  trajectory,
std::function< frc::Pose2d()>  pose,
frc::RamseteController  controller,
frc::SimpleMotorFeedforward< units::meters >  feedforward,
frc::DifferentialDriveKinematics  kinematics,
std::function< frc::DifferentialDriveWheelSpeeds()>  wheelSpeeds,
frc2::PIDController  leftController,
frc2::PIDController  rightController,
std::function< void(units::volt_t, units::volt_t)>  output,
std::span< Subsystem *const >  requirements = {} 
)

Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.

PID control and feedforward are handled internally, and outputs are scaled -12 to 12 representing units of volts.

Note: The controller will not set the outputVolts to zero upon completion of the path - this is left to the user, since it is not appropriate for paths with nonstationary endstates.

Parameters
trajectoryThe trajectory to follow.
poseA function that supplies the robot pose - use one of the odometry classes to provide this.
controllerThe RAMSETE controller used to follow the trajectory.
feedforwardA component for calculating the feedforward for the drive.
kinematicsThe kinematics for the robot drivetrain.
wheelSpeedsA function that supplies the speeds of the left and right sides of the robot drive.
leftControllerThe PIDController for the left side of the robot drive.
rightControllerThe PIDController for the right side of the robot drive.
outputA function that consumes the computed left and right outputs (in volts) for the robot drive.
requirementsThe subsystems to require.

◆ RamseteCommand() [3/4]

frc2::RamseteCommand::RamseteCommand ( frc::Trajectory  trajectory,
std::function< frc::Pose2d()>  pose,
frc::RamseteController  controller,
frc::DifferentialDriveKinematics  kinematics,
std::function< void(units::meters_per_second_t, units::meters_per_second_t)>  output,
std::initializer_list< Subsystem * >  requirements 
)

Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.

Performs no PID control and calculates no feedforwards; outputs are the raw wheel speeds from the RAMSETE controller, and will need to be converted into a usable form by the user.

Parameters
trajectoryThe trajectory to follow.
poseA function that supplies the robot pose - use one of the odometry classes to provide this.
controllerThe RAMSETE controller used to follow the trajectory.
kinematicsThe kinematics for the robot drivetrain.
outputA function that consumes the computed left and right wheel speeds.
requirementsThe subsystems to require.

◆ RamseteCommand() [4/4]

frc2::RamseteCommand::RamseteCommand ( frc::Trajectory  trajectory,
std::function< frc::Pose2d()>  pose,
frc::RamseteController  controller,
frc::DifferentialDriveKinematics  kinematics,
std::function< void(units::meters_per_second_t, units::meters_per_second_t)>  output,
std::span< Subsystem *const >  requirements = {} 
)

Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.

Performs no PID control and calculates no feedforwards; outputs are the raw wheel speeds from the RAMSETE controller, and will need to be converted into a usable form by the user.

Parameters
trajectoryThe trajectory to follow.
poseA function that supplies the robot pose - use one of the odometry classes to provide this.
controllerThe RAMSETE controller used to follow the trajectory.
kinematicsThe kinematics for the robot drivetrain.
outputA function that consumes the computed left and right wheel speeds.
requirementsThe subsystems to require.

Member Function Documentation

◆ End()

void frc2::RamseteCommand::End ( bool  interrupted)
overridevirtual

The action to take when the command ends.

Called when either the command finishes normally, or when it interrupted/canceled.

Parameters
interruptedwhether the command was interrupted/canceled

Reimplemented from frc2::Command.

◆ Execute()

void frc2::RamseteCommand::Execute ( )
overridevirtual

The main body of a command.

Called repeatedly while the command is scheduled.

Reimplemented from frc2::Command.

◆ Initialize()

void frc2::RamseteCommand::Initialize ( )
overridevirtual

The initial subroutine of a command.

Called once when the command is initially scheduled.

Reimplemented from frc2::Command.

◆ InitSendable()

void frc2::RamseteCommand::InitSendable ( wpi::SendableBuilder builder)
overridevirtual

Initializes this Sendable object.

Parameters
buildersendable builder

Implements wpi::Sendable.

◆ IsFinished()

bool frc2::RamseteCommand::IsFinished ( )
overridevirtual

Whether the command has finished.

Once a command finishes, the scheduler will call its end() method and un-schedule it.

Returns
whether the command has finished.

Reimplemented from frc2::Command.


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