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.math.controller;
006
007import edu.wpi.first.math.geometry.Pose2d;
008import edu.wpi.first.math.kinematics.ChassisSpeeds;
009import edu.wpi.first.math.trajectory.Trajectory;
010
011/**
012 * Ramsete is a nonlinear time-varying feedback controller for unicycle models that drives the model
013 * to a desired pose along a two-dimensional trajectory. Why would we need a nonlinear control law
014 * in addition to the linear ones we have used so far like PID? If we use the original approach with
015 * PID controllers for left and right position and velocity states, the controllers only deal with
016 * the local pose. If the robot deviates from the path, there is no way for the controllers to
017 * correct and the robot may not reach the desired global pose. This is due to multiple endpoints
018 * existing for the robot which have the same encoder path arc lengths.
019 *
020 * <p>Instead of using wheel path arc lengths (which are in the robot's local coordinate frame),
021 * nonlinear controllers like pure pursuit and Ramsete use global pose. The controller uses this
022 * extra information to guide a linear reference tracker like the PID controllers back in by
023 * adjusting the references of the PID controllers.
024 *
025 * <p>The paper "Control of Wheeled Mobile Robots: An Experimental Overview" describes a nonlinear
026 * controller for a wheeled vehicle with unicycle-like kinematics; a global pose consisting of x, y,
027 * and theta; and a desired pose consisting of x_d, y_d, and theta_d. We call it Ramsete because
028 * that's the acronym for the title of the book it came from in Italian ("Robotica Articolata e
029 * Mobile per i SErvizi e le TEcnologie").
030 *
031 * <p>See <a href="https://file.tavsys.net/control/ramsete-unicycle-controller.pdf">this paper</a>
032 * for a derivation and analysis.
033 */
034public class RamseteController {
035  private final double m_b;
036
037  private final double m_zeta;
038
039  private Pose2d m_poseError = Pose2d.kZero;
040  private Pose2d m_poseTolerance = Pose2d.kZero;
041  private boolean m_enabled = true;
042
043  /**
044   * Construct a Ramsete unicycle controller.
045   *
046   * @param b Tuning parameter (b &gt; 0 rad²/m²) for which larger values make convergence more
047   *     aggressive like a proportional term.
048   * @param zeta Tuning parameter (0 rad⁻¹ &lt; zeta &lt; 1 rad⁻¹) for which larger values provide
049   *     more damping in response.
050   * @deprecated Use LTVUnicycleController instead.
051   */
052  @Deprecated(since = "2025", forRemoval = true)
053  public RamseteController(double b, double zeta) {
054    m_b = b;
055    m_zeta = zeta;
056  }
057
058  /**
059   * Construct a Ramsete unicycle controller. The default arguments for b and zeta of 2.0 rad²/m²
060   * and 0.7 rad⁻¹ have been well-tested to produce desirable results.
061   *
062   * @deprecated Use LTVUnicycleController instead.
063   */
064  @Deprecated(since = "2025", forRemoval = true)
065  public RamseteController() {
066    this(2.0, 0.7);
067  }
068
069  /**
070   * Returns true if the pose error is within tolerance of the reference.
071   *
072   * @return True if the pose error is within tolerance of the reference.
073   */
074  public boolean atReference() {
075    final var eTranslate = m_poseError.getTranslation();
076    final var eRotate = m_poseError.getRotation();
077    final var tolTranslate = m_poseTolerance.getTranslation();
078    final var tolRotate = m_poseTolerance.getRotation();
079    return Math.abs(eTranslate.getX()) < tolTranslate.getX()
080        && Math.abs(eTranslate.getY()) < tolTranslate.getY()
081        && Math.abs(eRotate.getRadians()) < tolRotate.getRadians();
082  }
083
084  /**
085   * Sets the pose error which is considered tolerable for use with atReference().
086   *
087   * @param poseTolerance Pose error which is tolerable.
088   */
089  public void setTolerance(Pose2d poseTolerance) {
090    m_poseTolerance = poseTolerance;
091  }
092
093  /**
094   * Returns the next output of the Ramsete controller.
095   *
096   * <p>The reference pose, linear velocity, and angular velocity should come from a drivetrain
097   * trajectory.
098   *
099   * @param currentPose The current pose.
100   * @param poseRef The desired pose.
101   * @param linearVelocityRefMeters The desired linear velocity in meters per second.
102   * @param angularVelocityRefRadiansPerSecond The desired angular velocity in radians per second.
103   * @return The next controller output.
104   */
105  public ChassisSpeeds calculate(
106      Pose2d currentPose,
107      Pose2d poseRef,
108      double linearVelocityRefMeters,
109      double angularVelocityRefRadiansPerSecond) {
110    if (!m_enabled) {
111      return new ChassisSpeeds(linearVelocityRefMeters, 0.0, angularVelocityRefRadiansPerSecond);
112    }
113
114    m_poseError = poseRef.relativeTo(currentPose);
115
116    // Aliases for equation readability
117    final double eX = m_poseError.getX();
118    final double eY = m_poseError.getY();
119    final double eTheta = m_poseError.getRotation().getRadians();
120    final double vRef = linearVelocityRefMeters;
121    final double omegaRef = angularVelocityRefRadiansPerSecond;
122
123    // k = 2ζ√(ω_ref² + b v_ref²)
124    double k = 2.0 * m_zeta * Math.sqrt(Math.pow(omegaRef, 2) + m_b * Math.pow(vRef, 2));
125
126    // v_cmd = v_ref cos(e_θ) + k e_x
127    // ω_cmd = ω_ref + k e_θ + b v_ref sinc(e_θ) e_y
128    return new ChassisSpeeds(
129        vRef * m_poseError.getRotation().getCos() + k * eX,
130        0.0,
131        omegaRef + k * eTheta + m_b * vRef * sinc(eTheta) * eY);
132  }
133
134  /**
135   * Returns the next output of the Ramsete controller.
136   *
137   * <p>The reference pose, linear velocity, and angular velocity should come from a drivetrain
138   * trajectory.
139   *
140   * @param currentPose The current pose.
141   * @param desiredState The desired pose, linear velocity, and angular velocity from a trajectory.
142   * @return The next controller output.
143   */
144  public ChassisSpeeds calculate(Pose2d currentPose, Trajectory.State desiredState) {
145    return calculate(
146        currentPose,
147        desiredState.poseMeters,
148        desiredState.velocityMetersPerSecond,
149        desiredState.velocityMetersPerSecond * desiredState.curvatureRadPerMeter);
150  }
151
152  /**
153   * Enables and disables the controller for troubleshooting purposes.
154   *
155   * @param enabled If the controller is enabled or not.
156   */
157  public void setEnabled(boolean enabled) {
158    m_enabled = enabled;
159  }
160
161  /**
162   * Returns sin(x) / x.
163   *
164   * @param x Value of which to take sinc(x).
165   */
166  private static double sinc(double x) {
167    if (Math.abs(x) < 1e-9) {
168      return 1.0 - 1.0 / 6.0 * x * x;
169    } else {
170      return Math.sin(x) / x;
171    }
172  }
173}