A command that uses a RAMSETE controller to follow a trajectory with a differential drive.
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, 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 |
|
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
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
-
trajectory | The trajectory to follow. |
pose | A function that supplies the robot pose - use one of the odometry classes to provide this. |
controller | The RAMSETE controller used to follow the trajectory. |
feedforward | A component for calculating the feedforward for the drive. |
kinematics | The kinematics for the robot drivetrain. |
wheelSpeeds | A function that supplies the speeds of the left and right sides of the robot drive. |
leftController | The PIDController for the left side of the robot drive. |
rightController | The PIDController for the right side of the robot drive. |
output | A function that consumes the computed left and right outputs (in volts) for the robot drive. |
requirements | The subsystems to require. |