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