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