WPILibC++  2021.3.1
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 frc::Sendable frc::SendableHelper< CommandBase > frc::ErrorBase

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, wpi::ArrayRef< 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::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, wpi::ArrayRef< Subsystem * > 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...
 
- Public Member Functions inherited from frc2::CommandBase
void AddRequirements (std::initializer_list< Subsystem * > requirements)
 Adds the specified requirements to the command. More...
 
void AddRequirements (wpi::ArrayRef< Subsystem * > requirements)
 Adds the specified requirements to the command. More...
 
void AddRequirements (wpi::SmallSet< Subsystem *, 4 > requirements)
 
wpi::SmallSet< Subsystem *, 4 > GetRequirements () const override
 Specifies the set of subsystems used by this command. More...
 
void SetName (const wpi::Twine &name)
 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 (const wpi::Twine &subsystem)
 Sets the subsystem name of this Command. More...
 
void InitSendable (frc::SendableBuilder &builder) override
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from frc2::Command
 Command (const Command &)
 
Commandoperator= (const Command &)
 
 Command (Command &&)=default
 
Commandoperator= (Command &&)=default
 
ParallelRaceGroup WithTimeout (units::second_t duration) &&
 Decorates this command with a timeout. More...
 
ParallelRaceGroup WithInterrupt (std::function< bool()> condition) &&
 Decorates this command with an interrupt condition. More...
 
SequentialCommandGroup BeforeStarting (std::function< void()> toRun, std::initializer_list< Subsystem * > requirements) &&
 Decorates this command with a runnable to run before this command starts. More...
 
SequentialCommandGroup BeforeStarting (std::function< void()> toRun, wpi::ArrayRef< Subsystem * > requirements={}) &&
 Decorates this command with a runnable to run before this command starts. More...
 
SequentialCommandGroup AndThen (std::function< void()> toRun, std::initializer_list< Subsystem * > requirements) &&
 Decorates this command with a runnable to run after the command finishes. More...
 
SequentialCommandGroup AndThen (std::function< void()> toRun, wpi::ArrayRef< Subsystem * > requirements={}) &&
 Decorates this command with a runnable to run after the command finishes. More...
 
PerpetualCommand Perpetually () &&
 Decorates this command to run perpetually, ignoring its ordinary end conditions. More...
 
ProxyScheduleCommand AsProxy ()
 Decorates this command to run "by proxy" by wrapping it in a {}. More...
 
void Schedule (bool interruptible)
 Schedules this command. More...
 
void Schedule ()
 Schedules this command, defaulting to interruptible.
 
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 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...
 
- Public Member Functions inherited from frc::ErrorBase
 ErrorBase (const ErrorBase &)=default
 
ErrorBaseoperator= (const ErrorBase &)=default
 
 ErrorBase (ErrorBase &&)=default
 
ErrorBaseoperator= (ErrorBase &&)=default
 
virtual ErrorGetError ()
 Retrieve the current error. More...
 
virtual const ErrorGetError () const
 Retrieve the current error. More...
 
virtual void ClearError () const
 Clear the current error information associated with this sensor.
 
virtual void SetErrnoError (const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber) const
 Set error information associated with a C library call that set an error to the "errno" global variable. More...
 
virtual void SetImaqError (int success, const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber) const
 Set the current error information associated from the nivision Imaq API. More...
 
virtual void SetError (Error::Code code, const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber) const
 Set the current error information associated with this sensor. More...
 
virtual void SetErrorRange (Error::Code code, int32_t minRange, int32_t maxRange, int32_t requestedValue, const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber) const
 Set the current error information associated with this sensor. More...
 
virtual void SetWPIError (const wpi::Twine &errorMessage, Error::Code code, const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber) const
 Set the current error information associated with this sensor. More...
 
virtual void CloneError (const ErrorBase &rhs) const
 
virtual bool StatusIsFatal () const
 Check if the current error code represents a fatal error. More...
 
void ClearGlobalErrors ()
 Clear global errors.
 
- Public Member Functions inherited from frc::SendableHelper< CommandBase >
 SendableHelper (const SendableHelper &rhs)=default
 
 SendableHelper (SendableHelper &&rhs)
 
SendableHelperoperator= (const SendableHelper &rhs)=default
 
SendableHelperoperator= (SendableHelper &&rhs)
 
std::string GetName () const
 Gets the name of this Sendable object. More...
 
void SetName (const wpi::Twine &name)
 Sets the name of this Sendable object. More...
 
void SetName (const wpi::Twine &subsystem, const wpi::Twine &name)
 Sets both the subsystem name and device name of this Sendable object. More...
 
std::string GetSubsystem () const
 Gets the subsystem name of this Sendable object. More...
 
void SetSubsystem (const wpi::Twine &subsystem)
 Sets the subsystem name of this Sendable object. More...
 

Additional Inherited Members

- Static Public Member Functions inherited from frc::ErrorBase
static void SetGlobalError (Error::Code code, const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber)
 
static void SetGlobalWPIError (const wpi::Twine &errorMessage, const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber)
 
static Error GetGlobalError ()
 Retrieve the last global error.
 
static std::vector< ErrorGetGlobalErrors ()
 Retrieve all global errors.
 
- Protected Member Functions inherited from frc2::CommandHelper< CommandBase, RamseteCommand >
std::unique_ptr< CommandTransferOwnership () &&override
 
- Protected Member Functions inherited from frc2::Command
virtual std::unique_ptr< CommandTransferOwnership () &&=0
 Transfers ownership of this command to a unique pointer. More...
 
- Protected Member Functions inherited from frc::SendableHelper< CommandBase >
void SetName (const wpi::Twine &moduleType, int channel)
 Sets the name of the sensor with a channel number. More...
 
void SetName (const wpi::Twine &moduleType, int moduleNumber, int channel)
 Sets the name of the sensor with a module and channel number. More...
 
void AddChild (std::shared_ptr< Sendable > child)
 Add a child component. More...
 
void AddChild (void *child)
 Add a child component. More...
 
- Protected Attributes inherited from frc2::CommandBase
wpi::SmallSet< Subsystem *, 4 > m_requirements
 
- Protected Attributes inherited from frc2::Command
bool m_isGrouped = false
 
- Protected Attributes inherited from frc::ErrorBase
Error m_error
 

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.

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,
wpi::ArrayRef< 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() [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,
wpi::ArrayRef< 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.

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.

◆ 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: