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/controls-engineering-in-frc.pdf">Controls 032 * Engineering in the FIRST Robotics Competition</a> section on Ramsete unicycle controller for a 033 * derivation and analysis. 034 */ 035public class RamseteController { 036 @SuppressWarnings("MemberName") 037 private final double m_b; 038 039 @SuppressWarnings("MemberName") 040 private final double m_zeta; 041 042 private Pose2d m_poseError = new Pose2d(); 043 private Pose2d m_poseTolerance = new Pose2d(); 044 private boolean m_enabled = true; 045 046 /** 047 * Construct a Ramsete unicycle controller. 048 * 049 * @param b Tuning parameter (b > 0 rad²/m²) for which larger values make convergence more 050 * aggressive like a proportional term. 051 * @param zeta Tuning parameter (0 rad⁻¹ < zeta < 1 rad⁻¹) for which larger values provide 052 * more damping in response. 053 */ 054 @SuppressWarnings("ParameterName") 055 public RamseteController(double b, double zeta) { 056 m_b = b; 057 m_zeta = zeta; 058 } 059 060 /** 061 * Construct a Ramsete unicycle controller. The default arguments for b and zeta of 2.0 rad²/m² 062 * and 0.7 rad⁻¹ have been well-tested to produce desirable results. 063 */ 064 public RamseteController() { 065 this(2.0, 0.7); 066 } 067 068 /** 069 * Returns true if the pose error is within tolerance of the reference. 070 * 071 * @return True if the pose error is within tolerance of the reference. 072 */ 073 public boolean atReference() { 074 final var eTranslate = m_poseError.getTranslation(); 075 final var eRotate = m_poseError.getRotation(); 076 final var tolTranslate = m_poseTolerance.getTranslation(); 077 final var tolRotate = m_poseTolerance.getRotation(); 078 return Math.abs(eTranslate.getX()) < tolTranslate.getX() 079 && Math.abs(eTranslate.getY()) < tolTranslate.getY() 080 && Math.abs(eRotate.getRadians()) < tolRotate.getRadians(); 081 } 082 083 /** 084 * Sets the pose error which is considered tolerable for use with atReference(). 085 * 086 * @param poseTolerance Pose error which is tolerable. 087 */ 088 public void setTolerance(Pose2d poseTolerance) { 089 m_poseTolerance = poseTolerance; 090 } 091 092 /** 093 * Returns the next output of the Ramsete controller. 094 * 095 * <p>The reference pose, linear velocity, and angular velocity should come from a drivetrain 096 * trajectory. 097 * 098 * @param currentPose The current pose. 099 * @param poseRef The desired pose. 100 * @param linearVelocityRefMeters The desired linear velocity in meters per second. 101 * @param angularVelocityRefRadiansPerSecond The desired angular velocity in radians per second. 102 * @return The next controller output. 103 */ 104 @SuppressWarnings("LocalVariableName") 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 double k = 2.0 * m_zeta * Math.sqrt(Math.pow(omegaRef, 2) + m_b * Math.pow(vRef, 2)); 124 125 return new ChassisSpeeds( 126 vRef * m_poseError.getRotation().getCos() + k * eX, 127 0.0, 128 omegaRef + k * eTheta + m_b * vRef * sinc(eTheta) * eY); 129 } 130 131 /** 132 * Returns the next output of the Ramsete controller. 133 * 134 * <p>The reference pose, linear velocity, and angular velocity should come from a drivetrain 135 * trajectory. 136 * 137 * @param currentPose The current pose. 138 * @param desiredState The desired pose, linear velocity, and angular velocity from a trajectory. 139 * @return The next controller output. 140 */ 141 @SuppressWarnings("LocalVariableName") 142 public ChassisSpeeds calculate(Pose2d currentPose, Trajectory.State desiredState) { 143 return calculate( 144 currentPose, 145 desiredState.poseMeters, 146 desiredState.velocityMetersPerSecond, 147 desiredState.velocityMetersPerSecond * desiredState.curvatureRadPerMeter); 148 } 149 150 /** 151 * Enables and disables the controller for troubleshooting purposes. 152 * 153 * @param enabled If the controller is enabled or not. 154 */ 155 public void setEnabled(boolean enabled) { 156 m_enabled = enabled; 157 } 158 159 /** 160 * Returns sin(x) / x. 161 * 162 * @param x Value of which to take sinc(x). 163 */ 164 @SuppressWarnings("ParameterName") 165 private static double sinc(double x) { 166 if (Math.abs(x) < 1e-9) { 167 return 1.0 - 1.0 / 6.0 * x * x; 168 } else { 169 return Math.sin(x) / x; 170 } 171 } 172}