001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.wpilibj2.command;
006
007import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
008
009import edu.wpi.first.math.controller.PIDController;
010import edu.wpi.first.math.controller.RamseteController;
011import edu.wpi.first.math.controller.SimpleMotorFeedforward;
012import edu.wpi.first.math.geometry.Pose2d;
013import edu.wpi.first.math.kinematics.ChassisSpeeds;
014import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
015import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
016import edu.wpi.first.math.trajectory.Trajectory;
017import edu.wpi.first.util.sendable.SendableBuilder;
018import edu.wpi.first.wpilibj.Timer;
019import java.util.function.BiConsumer;
020import java.util.function.Supplier;
021
022/**
023 * A command that uses a RAMSETE controller ({@link RamseteController}) to follow a trajectory
024 * {@link Trajectory} with a differential drive.
025 *
026 * <p>The command handles trajectory-following, PID calculations, and feedforwards internally. This
027 * is intended to be a more-or-less "complete solution" that can be used by teams without a great
028 * deal of controls expertise.
029 *
030 * <p>Advanced teams seeking more flexibility (for example, those who wish to use the onboard PID
031 * functionality of a "smart" motor controller) may use the secondary constructor that omits the PID
032 * and feedforward functionality, returning only the raw wheel speeds from the RAMSETE controller.
033 *
034 * <p>This class is provided by the NewCommands VendorDep
035 */
036public class RamseteCommand extends Command {
037  private final Timer m_timer = new Timer();
038  private final boolean m_usePID;
039  private final Trajectory m_trajectory;
040  private final Supplier<Pose2d> m_pose;
041  private final RamseteController m_follower;
042  private final SimpleMotorFeedforward m_feedforward;
043  private final DifferentialDriveKinematics m_kinematics;
044  private final Supplier<DifferentialDriveWheelSpeeds> m_speeds;
045  private final PIDController m_leftController;
046  private final PIDController m_rightController;
047  private final BiConsumer<Double, Double> m_output;
048  private DifferentialDriveWheelSpeeds m_prevSpeeds = new DifferentialDriveWheelSpeeds();
049  private double m_prevLeftSpeedSetpoint; // m/s
050  private double m_prevRightSpeedSetpoint; // m/s
051  private double m_prevTime;
052
053  /**
054   * Constructs a new RamseteCommand that, when executed, will follow the provided trajectory. PID
055   * control and feedforward are handled internally, and outputs are scaled -12 to 12 representing
056   * units of volts.
057   *
058   * <p>Note: The controller will *not* set the outputVolts to zero upon completion of the path -
059   * this is left to the user, since it is not appropriate for paths with nonstationary endstates.
060   *
061   * @param trajectory The trajectory to follow.
062   * @param pose A function that supplies the robot pose - use one of the odometry classes to
063   *     provide this.
064   * @param controller The RAMSETE controller used to follow the trajectory.
065   * @param feedforward The feedforward to use for the drive.
066   * @param kinematics The kinematics for the robot drivetrain.
067   * @param wheelSpeeds A function that supplies the speeds of the left and right sides of the robot
068   *     drive.
069   * @param leftController The PIDController for the left side of the robot drive.
070   * @param rightController The PIDController for the right side of the robot drive.
071   * @param outputVolts A function that consumes the computed left and right outputs (in volts) for
072   *     the robot drive.
073   * @param requirements The subsystems to require.
074   * @deprecated Use LTVUnicycleController instead.
075   */
076  @Deprecated(since = "2025", forRemoval = true)
077  @SuppressWarnings("this-escape")
078  public RamseteCommand(
079      Trajectory trajectory,
080      Supplier<Pose2d> pose,
081      RamseteController controller,
082      SimpleMotorFeedforward feedforward,
083      DifferentialDriveKinematics kinematics,
084      Supplier<DifferentialDriveWheelSpeeds> wheelSpeeds,
085      PIDController leftController,
086      PIDController rightController,
087      BiConsumer<Double, Double> outputVolts,
088      Subsystem... requirements) {
089    m_trajectory = requireNonNullParam(trajectory, "trajectory", "RamseteCommand");
090    m_pose = requireNonNullParam(pose, "pose", "RamseteCommand");
091    m_follower = requireNonNullParam(controller, "controller", "RamseteCommand");
092    m_feedforward = feedforward;
093    m_kinematics = requireNonNullParam(kinematics, "kinematics", "RamseteCommand");
094    m_speeds = requireNonNullParam(wheelSpeeds, "wheelSpeeds", "RamseteCommand");
095    m_leftController = requireNonNullParam(leftController, "leftController", "RamseteCommand");
096    m_rightController = requireNonNullParam(rightController, "rightController", "RamseteCommand");
097    m_output = requireNonNullParam(outputVolts, "outputVolts", "RamseteCommand");
098
099    m_usePID = true;
100
101    addRequirements(requirements);
102  }
103
104  /**
105   * Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.
106   * Performs no PID control and calculates no feedforwards; outputs are the raw wheel speeds from
107   * the RAMSETE controller, and will need to be converted into a usable form by the user.
108   *
109   * @param trajectory The trajectory to follow.
110   * @param pose A function that supplies the robot pose - use one of the odometry classes to
111   *     provide this.
112   * @param follower The RAMSETE follower used to follow the trajectory.
113   * @param kinematics The kinematics for the robot drivetrain.
114   * @param outputMetersPerSecond A function that consumes the computed left and right wheel speeds.
115   * @param requirements The subsystems to require.
116   * @deprecated Use LTVUnicycleController instead.
117   */
118  @Deprecated(since = "2025", forRemoval = true)
119  @SuppressWarnings("this-escape")
120  public RamseteCommand(
121      Trajectory trajectory,
122      Supplier<Pose2d> pose,
123      RamseteController follower,
124      DifferentialDriveKinematics kinematics,
125      BiConsumer<Double, Double> outputMetersPerSecond,
126      Subsystem... requirements) {
127    m_trajectory = requireNonNullParam(trajectory, "trajectory", "RamseteCommand");
128    m_pose = requireNonNullParam(pose, "pose", "RamseteCommand");
129    m_follower = requireNonNullParam(follower, "follower", "RamseteCommand");
130    m_kinematics = requireNonNullParam(kinematics, "kinematics", "RamseteCommand");
131    m_output =
132        requireNonNullParam(outputMetersPerSecond, "outputMetersPerSecond", "RamseteCommand");
133
134    m_feedforward = null;
135    m_speeds = null;
136    m_leftController = null;
137    m_rightController = null;
138
139    m_usePID = false;
140
141    addRequirements(requirements);
142  }
143
144  @Override
145  public void initialize() {
146    m_prevTime = -1;
147    var initialState = m_trajectory.sample(0);
148    m_prevSpeeds =
149        m_kinematics.toWheelSpeeds(
150            new ChassisSpeeds(
151                initialState.velocityMetersPerSecond,
152                0,
153                initialState.curvatureRadPerMeter * initialState.velocityMetersPerSecond));
154    m_prevLeftSpeedSetpoint = m_prevSpeeds.leftMetersPerSecond;
155    m_prevRightSpeedSetpoint = m_prevSpeeds.rightMetersPerSecond;
156    m_timer.restart();
157    if (m_usePID) {
158      m_leftController.reset();
159      m_rightController.reset();
160    }
161  }
162
163  @Override
164  public void execute() {
165    double curTime = m_timer.get();
166
167    if (m_prevTime < 0) {
168      m_output.accept(0.0, 0.0);
169      m_prevTime = curTime;
170      return;
171    }
172
173    var targetWheelSpeeds =
174        m_kinematics.toWheelSpeeds(
175            m_follower.calculate(m_pose.get(), m_trajectory.sample(curTime)));
176
177    double leftSpeedSetpoint = targetWheelSpeeds.leftMetersPerSecond;
178    double rightSpeedSetpoint = targetWheelSpeeds.rightMetersPerSecond;
179
180    double leftOutput;
181    double rightOutput;
182
183    if (m_usePID) {
184      double leftFeedforward =
185          m_feedforward.calculateWithVelocities(m_prevLeftSpeedSetpoint, leftSpeedSetpoint);
186
187      double rightFeedforward =
188          m_feedforward.calculateWithVelocities(m_prevRightSpeedSetpoint, rightSpeedSetpoint);
189
190      leftOutput =
191          leftFeedforward
192              + m_leftController.calculate(m_speeds.get().leftMetersPerSecond, leftSpeedSetpoint);
193
194      rightOutput =
195          rightFeedforward
196              + m_rightController.calculate(
197                  m_speeds.get().rightMetersPerSecond, rightSpeedSetpoint);
198    } else {
199      leftOutput = leftSpeedSetpoint;
200      rightOutput = rightSpeedSetpoint;
201    }
202
203    m_output.accept(leftOutput, rightOutput);
204    m_prevSpeeds = targetWheelSpeeds;
205    m_prevTime = curTime;
206  }
207
208  @Override
209  public void end(boolean interrupted) {
210    m_timer.stop();
211
212    if (interrupted) {
213      m_output.accept(0.0, 0.0);
214    }
215  }
216
217  @Override
218  public boolean isFinished() {
219    return m_timer.hasElapsed(m_trajectory.getTotalTimeSeconds());
220  }
221
222  @Override
223  public void initSendable(SendableBuilder builder) {
224    super.initSendable(builder);
225    builder.addDoubleProperty("leftVelocity", () -> m_prevSpeeds.leftMetersPerSecond, null);
226    builder.addDoubleProperty("rightVelocity", () -> m_prevSpeeds.rightMetersPerSecond, null);
227  }
228}