WPILibC++ 2024.3.2
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< Command, RamseteCommand >

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, frc::PIDController leftController, frc::PIDController rightController, std::function< void(units::volt_t, units::volt_t)> output, Requirements 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, Requirements requirements={})
 Constructs a new RamseteCommand that, when executed, will follow the provided trajectory. More...
 
void Initialize () override
 
void Execute () override
 
void End (bool interrupted) override
 
bool IsFinished () override
 
void InitSendable (wpi::SendableBuilder &builder) override
 
- Public Member Functions inherited from frc2::CommandHelper< Command, RamseteCommand >
 CommandHelper ()=default
 
CommandPtr ToPtr () &&override
 

Additional Inherited Members

- Protected Member Functions inherited from frc2::CommandHelper< Command, RamseteCommand >
std::unique_ptr< CommandTransferOwnership () &&override
 

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/2]

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,
frc::PIDController  leftController,
frc::PIDController  rightController,
std::function< void(units::volt_t, units::volt_t)>  output,
Requirements  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/2]

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,
Requirements  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)
override

◆ Execute()

void frc2::RamseteCommand::Execute ( )
override

◆ Initialize()

void frc2::RamseteCommand::Initialize ( )
override

◆ InitSendable()

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

◆ IsFinished()

bool frc2::RamseteCommand::IsFinished ( )
override

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