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.kinematics;
006
007import edu.wpi.first.math.MathSharedStore;
008import edu.wpi.first.math.MathUsageId;
009import edu.wpi.first.math.geometry.Rotation2d;
010import edu.wpi.first.math.geometry.Translation2d;
011import edu.wpi.first.math.geometry.Twist2d;
012import java.util.Arrays;
013import java.util.Collections;
014import org.ejml.simple.SimpleMatrix;
015
016/**
017 * Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual
018 * module states (speed and angle).
019 *
020 * <p>The inverse kinematics (converting from a desired chassis velocity to individual module
021 * states) uses the relative locations of the modules with respect to the center of rotation. The
022 * center of rotation for inverse kinematics is also variable. This means that you can set your
023 * center of rotation in a corner of the robot to perform special evasion maneuvers.
024 *
025 * <p>Forward kinematics (converting an array of module states into the overall chassis motion) is
026 * performs the exact opposite of what inverse kinematics does. Since this is an overdetermined
027 * system (more equations than variables), we use a least-squares approximation.
028 *
029 * <p>The inverse kinematics: [moduleStates] = [moduleLocations] * [chassisSpeeds] We take the
030 * Moore-Penrose pseudoinverse of [moduleLocations] and then multiply by [moduleStates] to get our
031 * chassis speeds.
032 *
033 * <p>Forward kinematics is also used for odometry -- determining the position of the robot on the
034 * field using encoders and a gyro.
035 */
036public class SwerveDriveKinematics {
037  private final SimpleMatrix m_inverseKinematics;
038  private final SimpleMatrix m_forwardKinematics;
039
040  private final int m_numModules;
041  private final Translation2d[] m_modules;
042  private SwerveModuleState[] m_moduleStates;
043  private Translation2d m_prevCoR = new Translation2d();
044
045  /**
046   * Constructs a swerve drive kinematics object. This takes in a variable number of wheel locations
047   * as Translation2d objects. The order in which you pass in the wheel locations is the same order
048   * that you will receive the module states when performing inverse kinematics. It is also expected
049   * that you pass in the module states in the same order when calling the forward kinematics
050   * methods.
051   *
052   * @param wheelsMeters The locations of the wheels relative to the physical center of the robot.
053   */
054  public SwerveDriveKinematics(Translation2d... wheelsMeters) {
055    if (wheelsMeters.length < 2) {
056      throw new IllegalArgumentException("A swerve drive requires at least two modules");
057    }
058    m_numModules = wheelsMeters.length;
059    m_modules = Arrays.copyOf(wheelsMeters, m_numModules);
060    m_moduleStates = new SwerveModuleState[m_numModules];
061    Arrays.fill(m_moduleStates, new SwerveModuleState());
062    m_inverseKinematics = new SimpleMatrix(m_numModules * 2, 3);
063
064    for (int i = 0; i < m_numModules; i++) {
065      m_inverseKinematics.setRow(i * 2 + 0, 0, /* Start Data */ 1, 0, -m_modules[i].getY());
066      m_inverseKinematics.setRow(i * 2 + 1, 0, /* Start Data */ 0, 1, +m_modules[i].getX());
067    }
068    m_forwardKinematics = m_inverseKinematics.pseudoInverse();
069
070    MathSharedStore.reportUsage(MathUsageId.kKinematics_SwerveDrive, 1);
071  }
072
073  /**
074   * Performs inverse kinematics to return the module states from a desired chassis velocity. This
075   * method is often used to convert joystick values into module speeds and angles.
076   *
077   * <p>This function also supports variable centers of rotation. During normal operations, the
078   * center of rotation is usually the same as the physical center of the robot; therefore, the
079   * argument is defaulted to that use case. However, if you wish to change the center of rotation
080   * for evasive maneuvers, vision alignment, or for any other use case, you can do so.
081   *
082   * <p>In the case that the desired chassis speeds are zero (i.e. the robot will be stationary),
083   * the previously calculated module angle will be maintained.
084   *
085   * @param chassisSpeeds The desired chassis speed.
086   * @param centerOfRotationMeters The center of rotation. For example, if you set the center of
087   *     rotation at one corner of the robot and provide a chassis speed that only has a dtheta
088   *     component, the robot will rotate around that corner.
089   * @return An array containing the module states. Use caution because these module states are not
090   *     normalized. Sometimes, a user input may cause one of the module speeds to go above the
091   *     attainable max velocity. Use the {@link #desaturateWheelSpeeds(SwerveModuleState[], double)
092   *     DesaturateWheelSpeeds} function to rectify this issue.
093   */
094  @SuppressWarnings("PMD.MethodReturnsInternalArray")
095  public SwerveModuleState[] toSwerveModuleStates(
096      ChassisSpeeds chassisSpeeds, Translation2d centerOfRotationMeters) {
097    if (chassisSpeeds.vxMetersPerSecond == 0.0
098        && chassisSpeeds.vyMetersPerSecond == 0.0
099        && chassisSpeeds.omegaRadiansPerSecond == 0.0) {
100      SwerveModuleState[] newStates = new SwerveModuleState[m_numModules];
101      for (int i = 0; i < m_numModules; i++) {
102        newStates[i] = new SwerveModuleState(0.0, m_moduleStates[i].angle);
103      }
104
105      m_moduleStates = newStates;
106      return m_moduleStates;
107    }
108
109    if (!centerOfRotationMeters.equals(m_prevCoR)) {
110      for (int i = 0; i < m_numModules; i++) {
111        m_inverseKinematics.setRow(
112            i * 2 + 0,
113            0, /* Start Data */
114            1,
115            0,
116            -m_modules[i].getY() + centerOfRotationMeters.getY());
117        m_inverseKinematics.setRow(
118            i * 2 + 1,
119            0, /* Start Data */
120            0,
121            1,
122            +m_modules[i].getX() - centerOfRotationMeters.getX());
123      }
124      m_prevCoR = centerOfRotationMeters;
125    }
126
127    var chassisSpeedsVector = new SimpleMatrix(3, 1);
128    chassisSpeedsVector.setColumn(
129        0,
130        0,
131        chassisSpeeds.vxMetersPerSecond,
132        chassisSpeeds.vyMetersPerSecond,
133        chassisSpeeds.omegaRadiansPerSecond);
134
135    var moduleStatesMatrix = m_inverseKinematics.mult(chassisSpeedsVector);
136
137    m_moduleStates = new SwerveModuleState[m_numModules];
138    for (int i = 0; i < m_numModules; i++) {
139      double x = moduleStatesMatrix.get(i * 2, 0);
140      double y = moduleStatesMatrix.get(i * 2 + 1, 0);
141
142      double speed = Math.hypot(x, y);
143      Rotation2d angle = new Rotation2d(x, y);
144
145      m_moduleStates[i] = new SwerveModuleState(speed, angle);
146    }
147
148    return m_moduleStates;
149  }
150
151  /**
152   * Performs inverse kinematics. See {@link #toSwerveModuleStates(ChassisSpeeds, Translation2d)}
153   * toSwerveModuleStates for more information.
154   *
155   * @param chassisSpeeds The desired chassis speed.
156   * @return An array containing the module states.
157   */
158  public SwerveModuleState[] toSwerveModuleStates(ChassisSpeeds chassisSpeeds) {
159    return toSwerveModuleStates(chassisSpeeds, new Translation2d());
160  }
161
162  /**
163   * Performs forward kinematics to return the resulting chassis state from the given module states.
164   * This method is often used for odometry -- determining the robot's position on the field using
165   * data from the real-world speed and angle of each module on the robot.
166   *
167   * @param wheelStates The state of the modules (as a SwerveModuleState type) as measured from
168   *     respective encoders and gyros. The order of the swerve module states should be same as
169   *     passed into the constructor of this class.
170   * @return The resulting chassis speed.
171   */
172  public ChassisSpeeds toChassisSpeeds(SwerveModuleState... wheelStates) {
173    if (wheelStates.length != m_numModules) {
174      throw new IllegalArgumentException(
175          "Number of modules is not consistent with number of wheel locations provided in "
176              + "constructor");
177    }
178    var moduleStatesMatrix = new SimpleMatrix(m_numModules * 2, 1);
179
180    for (int i = 0; i < m_numModules; i++) {
181      var module = wheelStates[i];
182      moduleStatesMatrix.set(i * 2, 0, module.speedMetersPerSecond * module.angle.getCos());
183      moduleStatesMatrix.set(i * 2 + 1, module.speedMetersPerSecond * module.angle.getSin());
184    }
185
186    var chassisSpeedsVector = m_forwardKinematics.mult(moduleStatesMatrix);
187    return new ChassisSpeeds(
188        chassisSpeedsVector.get(0, 0),
189        chassisSpeedsVector.get(1, 0),
190        chassisSpeedsVector.get(2, 0));
191  }
192
193  /**
194   * Performs forward kinematics to return the resulting chassis state from the given module states.
195   * This method is often used for odometry -- determining the robot's position on the field using
196   * data from the real-world speed and angle of each module on the robot.
197   *
198   * @param wheelDeltas The latest change in position of the modules (as a SwerveModulePosition
199   *     type) as measured from respective encoders and gyros. The order of the swerve module states
200   *     should be same as passed into the constructor of this class.
201   * @return The resulting Twist2d.
202   */
203  public Twist2d toTwist2d(SwerveModulePosition... wheelDeltas) {
204    if (wheelDeltas.length != m_numModules) {
205      throw new IllegalArgumentException(
206          "Number of modules is not consistent with number of wheel locations provided in "
207              + "constructor");
208    }
209    var moduleDeltaMatrix = new SimpleMatrix(m_numModules * 2, 1);
210
211    for (int i = 0; i < m_numModules; i++) {
212      var module = wheelDeltas[i];
213      moduleDeltaMatrix.set(i * 2, 0, module.distanceMeters * module.angle.getCos());
214      moduleDeltaMatrix.set(i * 2 + 1, module.distanceMeters * module.angle.getSin());
215    }
216
217    var chassisDeltaVector = m_forwardKinematics.mult(moduleDeltaMatrix);
218    return new Twist2d(
219        chassisDeltaVector.get(0, 0), chassisDeltaVector.get(1, 0), chassisDeltaVector.get(2, 0));
220  }
221
222  /**
223   * Renormalizes the wheel speeds if any individual speed is above the specified maximum.
224   *
225   * <p>Sometimes, after inverse kinematics, the requested speed from one or more modules may be
226   * above the max attainable speed for the driving motor on that module. To fix this issue, one can
227   * reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the
228   * absolute threshold, while maintaining the ratio of speeds between modules.
229   *
230   * @param moduleStates Reference to array of module states. The array will be mutated with the
231   *     normalized speeds!
232   * @param attainableMaxSpeedMetersPerSecond The absolute max speed that a module can reach.
233   */
234  public static void desaturateWheelSpeeds(
235      SwerveModuleState[] moduleStates, double attainableMaxSpeedMetersPerSecond) {
236    double realMaxSpeed = Collections.max(Arrays.asList(moduleStates)).speedMetersPerSecond;
237    if (realMaxSpeed > attainableMaxSpeedMetersPerSecond) {
238      for (SwerveModuleState moduleState : moduleStates) {
239        moduleState.speedMetersPerSecond =
240            moduleState.speedMetersPerSecond / realMaxSpeed * attainableMaxSpeedMetersPerSecond;
241      }
242    }
243  }
244
245  /**
246   * Renormalizes the wheel speeds if any individual speed is above the specified maximum, as well
247   * as getting rid of joystick saturation at edges of joystick.
248   *
249   * <p>Sometimes, after inverse kinematics, the requested speed from one or more modules may be
250   * above the max attainable speed for the driving motor on that module. To fix this issue, one can
251   * reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the
252   * absolute threshold, while maintaining the ratio of speeds between modules.
253   *
254   * @param moduleStates Reference to array of module states. The array will be mutated with the
255   *     normalized speeds!
256   * @param currentChassisSpeed The current speed of the robot
257   * @param attainableMaxModuleSpeedMetersPerSecond The absolute max speed that a module can reach
258   * @param attainableMaxTranslationalSpeedMetersPerSecond The absolute max speed that your robot
259   *     can reach while translating
260   * @param attainableMaxRotationalVelocityRadiansPerSecond The absolute max speed the robot can
261   *     reach while rotating
262   */
263  public static void desaturateWheelSpeeds(
264      SwerveModuleState[] moduleStates,
265      ChassisSpeeds currentChassisSpeed,
266      double attainableMaxModuleSpeedMetersPerSecond,
267      double attainableMaxTranslationalSpeedMetersPerSecond,
268      double attainableMaxRotationalVelocityRadiansPerSecond) {
269    double realMaxSpeed = Collections.max(Arrays.asList(moduleStates)).speedMetersPerSecond;
270
271    if (attainableMaxTranslationalSpeedMetersPerSecond == 0
272        || attainableMaxRotationalVelocityRadiansPerSecond == 0
273        || realMaxSpeed == 0) {
274      return;
275    }
276    double translationalK =
277        Math.hypot(currentChassisSpeed.vxMetersPerSecond, currentChassisSpeed.vyMetersPerSecond)
278            / attainableMaxTranslationalSpeedMetersPerSecond;
279    double rotationalK =
280        Math.abs(currentChassisSpeed.omegaRadiansPerSecond)
281            / attainableMaxRotationalVelocityRadiansPerSecond;
282    double k = Math.max(translationalK, rotationalK);
283    double scale = Math.min(k * attainableMaxModuleSpeedMetersPerSecond / realMaxSpeed, 1);
284    for (SwerveModuleState moduleState : moduleStates) {
285      moduleState.speedMetersPerSecond *= scale;
286    }
287  }
288}