public class RamseteCommand extends java.lang.Object implements Command
RamseteController) to follow a trajectory
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.
| Constructor and Description |
|---|
RamseteCommand(Trajectory trajectory,
java.util.function.Supplier<Pose2d> pose,
RamseteController follower,
DifferentialDriveKinematics kinematics,
java.util.function.BiConsumer<java.lang.Double,java.lang.Double> outputMetersPerSecond)
Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.
|
RamseteCommand(Trajectory trajectory,
java.util.function.Supplier<Pose2d> pose,
RamseteController controller,
SimpleMotorFeedforward feedforward,
DifferentialDriveKinematics kinematics,
java.util.function.Supplier<DifferentialDriveWheelSpeeds> wheelSpeeds,
PIDController leftController,
PIDController rightController,
java.util.function.BiConsumer<java.lang.Double,java.lang.Double> outputVolts)
Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.
|
| Modifier and Type | Method and Description |
|---|---|
void |
end()
The action to take when the command ends.
|
void |
execute()
The main body of a command.
|
void |
initialize()
The initial subroutine of a command.
|
boolean |
isFinished()
Whether the command has finished.
|
public RamseteCommand(Trajectory trajectory, java.util.function.Supplier<Pose2d> pose, RamseteController controller, SimpleMotorFeedforward feedforward, DifferentialDriveKinematics kinematics, java.util.function.Supplier<DifferentialDriveWheelSpeeds> wheelSpeeds, PIDController leftController, PIDController rightController, java.util.function.BiConsumer<java.lang.Double,java.lang.Double> outputVolts)
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.
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 - The feedforward to use 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.outputVolts - A function that consumes the computed left and right
outputs (in volts) for the robot drive.public RamseteCommand(Trajectory trajectory, java.util.function.Supplier<Pose2d> pose, RamseteController follower, DifferentialDriveKinematics kinematics, java.util.function.BiConsumer<java.lang.Double,java.lang.Double> outputMetersPerSecond)
trajectory - The trajectory to follow.pose - A function that supplies the robot pose - use one of
the odometry classes to provide this.follower - The RAMSETE follower used to follow the trajectory.kinematics - The kinematics for the robot drivetrain.outputMetersPerSecond - A function that consumes the computed left and right
wheel speeds.public void initialize()
Commandinitialize in interface Commandpublic void execute()
Commandpublic void end()
Commandpublic boolean isFinished()
CommandisFinished in interface Command