Class RamseteCommand

java.lang.Object
edu.wpi.first.wpilibj2.command.CommandBase
edu.wpi.first.wpilibj2.command.RamseteCommand
All Implemented Interfaces:
Sendable, Command

public class RamseteCommand
extends CommandBase
A command that uses a RAMSETE controller (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 Details

    • RamseteCommand

      public RamseteCommand​(Trajectory trajectory, Supplier<Pose2d> pose, RamseteController controller, SimpleMotorFeedforward feedforward, DifferentialDriveKinematics kinematics, Supplier<DifferentialDriveWheelSpeeds> wheelSpeeds, PIDController leftController, PIDController rightController, BiConsumer<Double,​Double> outputVolts, 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:
      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.
      requirements - The subsystems to require.
    • RamseteCommand

      public RamseteCommand​(Trajectory trajectory, Supplier<Pose2d> pose, RamseteController follower, DifferentialDriveKinematics kinematics, BiConsumer<Double,​Double> outputMetersPerSecond, 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:
      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.
      requirements - The subsystems to require.
  • Method Details

    • initialize

      public void initialize()
      Description copied from interface: Command
      The initial subroutine of a command. Called once when the command is initially scheduled.
    • execute

      public void execute()
      Description copied from interface: Command
      The main body of a command. Called repeatedly while the command is scheduled.
    • end

      public void end​(boolean interrupted)
      Description copied from interface: Command
      The action to take when the command ends. Called when either the command finishes normally, or when it interrupted/canceled.

      Do not schedule commands here that share requirements with this command. Use Command.andThen(Command...) instead.

      Parameters:
      interrupted - whether the command was interrupted/canceled
    • isFinished

      public boolean isFinished()
      Description copied from interface: Command
      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.