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