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_prevTime;
050
051  /**
052   * Constructs a new RamseteCommand that, when executed, will follow the provided trajectory. PID
053   * control and feedforward are handled internally, and outputs are scaled -12 to 12 representing
054   * units of volts.
055   *
056   * <p>Note: The controller will *not* set the outputVolts to zero upon completion of the path -
057   * this is left to the user, since it is not appropriate for paths with nonstationary endstates.
058   *
059   * @param trajectory The trajectory to follow.
060   * @param pose A function that supplies the robot pose - use one of the odometry classes to
061   *     provide this.
062   * @param controller The RAMSETE controller used to follow the trajectory.
063   * @param feedforward The feedforward to use for the drive.
064   * @param kinematics The kinematics for the robot drivetrain.
065   * @param wheelSpeeds A function that supplies the speeds of the left and right sides of the robot
066   *     drive.
067   * @param leftController The PIDController for the left side of the robot drive.
068   * @param rightController The PIDController for the right side of the robot drive.
069   * @param outputVolts A function that consumes the computed left and right outputs (in volts) for
070   *     the robot drive.
071   * @param requirements The subsystems to require.
072   */
073  @SuppressWarnings("this-escape")
074  public RamseteCommand(
075      Trajectory trajectory,
076      Supplier<Pose2d> pose,
077      RamseteController controller,
078      SimpleMotorFeedforward feedforward,
079      DifferentialDriveKinematics kinematics,
080      Supplier<DifferentialDriveWheelSpeeds> wheelSpeeds,
081      PIDController leftController,
082      PIDController rightController,
083      BiConsumer<Double, Double> outputVolts,
084      Subsystem... requirements) {
085    m_trajectory = requireNonNullParam(trajectory, "trajectory", "RamseteCommand");
086    m_pose = requireNonNullParam(pose, "pose", "RamseteCommand");
087    m_follower = requireNonNullParam(controller, "controller", "RamseteCommand");
088    m_feedforward = feedforward;
089    m_kinematics = requireNonNullParam(kinematics, "kinematics", "RamseteCommand");
090    m_speeds = requireNonNullParam(wheelSpeeds, "wheelSpeeds", "RamseteCommand");
091    m_leftController = requireNonNullParam(leftController, "leftController", "RamseteCommand");
092    m_rightController = requireNonNullParam(rightController, "rightController", "RamseteCommand");
093    m_output = requireNonNullParam(outputVolts, "outputVolts", "RamseteCommand");
094
095    m_usePID = true;
096
097    addRequirements(requirements);
098  }
099
100  /**
101   * Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.
102   * Performs no PID control and calculates no feedforwards; outputs are the raw wheel speeds from
103   * the RAMSETE controller, and will need to be converted into a usable form by the user.
104   *
105   * @param trajectory The trajectory to follow.
106   * @param pose A function that supplies the robot pose - use one of the odometry classes to
107   *     provide this.
108   * @param follower The RAMSETE follower used to follow the trajectory.
109   * @param kinematics The kinematics for the robot drivetrain.
110   * @param outputMetersPerSecond A function that consumes the computed left and right wheel speeds.
111   * @param requirements The subsystems to require.
112   */
113  @SuppressWarnings("this-escape")
114  public RamseteCommand(
115      Trajectory trajectory,
116      Supplier<Pose2d> pose,
117      RamseteController follower,
118      DifferentialDriveKinematics kinematics,
119      BiConsumer<Double, Double> outputMetersPerSecond,
120      Subsystem... requirements) {
121    m_trajectory = requireNonNullParam(trajectory, "trajectory", "RamseteCommand");
122    m_pose = requireNonNullParam(pose, "pose", "RamseteCommand");
123    m_follower = requireNonNullParam(follower, "follower", "RamseteCommand");
124    m_kinematics = requireNonNullParam(kinematics, "kinematics", "RamseteCommand");
125    m_output =
126        requireNonNullParam(outputMetersPerSecond, "outputMetersPerSecond", "RamseteCommand");
127
128    m_feedforward = null;
129    m_speeds = null;
130    m_leftController = null;
131    m_rightController = null;
132
133    m_usePID = false;
134
135    addRequirements(requirements);
136  }
137
138  @Override
139  public void initialize() {
140    m_prevTime = -1;
141    var initialState = m_trajectory.sample(0);
142    m_prevSpeeds =
143        m_kinematics.toWheelSpeeds(
144            new ChassisSpeeds(
145                initialState.velocityMetersPerSecond,
146                0,
147                initialState.curvatureRadPerMeter * initialState.velocityMetersPerSecond));
148    m_timer.restart();
149    if (m_usePID) {
150      m_leftController.reset();
151      m_rightController.reset();
152    }
153  }
154
155  @Override
156  public void execute() {
157    double curTime = m_timer.get();
158    double dt = curTime - m_prevTime;
159
160    if (m_prevTime < 0) {
161      m_output.accept(0.0, 0.0);
162      m_prevTime = curTime;
163      return;
164    }
165
166    var targetWheelSpeeds =
167        m_kinematics.toWheelSpeeds(
168            m_follower.calculate(m_pose.get(), m_trajectory.sample(curTime)));
169
170    var leftSpeedSetpoint = targetWheelSpeeds.leftMetersPerSecond;
171    var rightSpeedSetpoint = targetWheelSpeeds.rightMetersPerSecond;
172
173    double leftOutput;
174    double rightOutput;
175
176    if (m_usePID) {
177      double leftFeedforward =
178          m_feedforward.calculate(
179              leftSpeedSetpoint, (leftSpeedSetpoint - m_prevSpeeds.leftMetersPerSecond) / dt);
180
181      double rightFeedforward =
182          m_feedforward.calculate(
183              rightSpeedSetpoint, (rightSpeedSetpoint - m_prevSpeeds.rightMetersPerSecond) / dt);
184
185      leftOutput =
186          leftFeedforward
187              + m_leftController.calculate(m_speeds.get().leftMetersPerSecond, leftSpeedSetpoint);
188
189      rightOutput =
190          rightFeedforward
191              + m_rightController.calculate(
192                  m_speeds.get().rightMetersPerSecond, rightSpeedSetpoint);
193    } else {
194      leftOutput = leftSpeedSetpoint;
195      rightOutput = rightSpeedSetpoint;
196    }
197
198    m_output.accept(leftOutput, rightOutput);
199    m_prevSpeeds = targetWheelSpeeds;
200    m_prevTime = curTime;
201  }
202
203  @Override
204  public void end(boolean interrupted) {
205    m_timer.stop();
206
207    if (interrupted) {
208      m_output.accept(0.0, 0.0);
209    }
210  }
211
212  @Override
213  public boolean isFinished() {
214    return m_timer.hasElapsed(m_trajectory.getTotalTimeSeconds());
215  }
216
217  @Override
218  public void initSendable(SendableBuilder builder) {
219    super.initSendable(builder);
220    builder.addDoubleProperty("leftVelocity", () -> m_prevSpeeds.leftMetersPerSecond, null);
221    builder.addDoubleProperty("rightVelocity", () -> m_prevSpeeds.rightMetersPerSecond, null);
222  }
223}