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 java.util.Arrays; 012import java.util.Collections; 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 set 022 * your 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 private final SimpleMatrix m_inverseKinematics; 037 private final SimpleMatrix m_forwardKinematics; 038 039 private final int m_numModules; 040 private final Translation2d[] m_modules; 041 private Translation2d m_prevCoR = new Translation2d(); 042 043 /** 044 * Constructs a swerve drive kinematics object. This takes in a variable number of wheel locations 045 * as Translation2ds. The order in which you pass in the wheel locations is the same order that 046 * you will receive the module states when performing inverse kinematics. It is also expected that 047 * you pass in the module states in the same order when calling the forward kinematics methods. 048 * 049 * @param wheelsMeters The locations of the wheels relative to the physical center of the robot. 050 */ 051 public SwerveDriveKinematics(Translation2d... wheelsMeters) { 052 if (wheelsMeters.length < 2) { 053 throw new IllegalArgumentException("A swerve drive requires at least two modules"); 054 } 055 m_numModules = wheelsMeters.length; 056 m_modules = Arrays.copyOf(wheelsMeters, m_numModules); 057 m_inverseKinematics = new SimpleMatrix(m_numModules * 2, 3); 058 059 for (int i = 0; i < m_numModules; i++) { 060 m_inverseKinematics.setRow(i * 2 + 0, 0, /* Start Data */ 1, 0, -m_modules[i].getY()); 061 m_inverseKinematics.setRow(i * 2 + 1, 0, /* Start Data */ 0, 1, +m_modules[i].getX()); 062 } 063 m_forwardKinematics = m_inverseKinematics.pseudoInverse(); 064 065 MathSharedStore.reportUsage(MathUsageId.kKinematics_SwerveDrive, 1); 066 } 067 068 /** 069 * Performs inverse kinematics to return the module states from a desired chassis velocity. This 070 * method is often used to convert joystick values into module speeds and angles. 071 * 072 * <p>This function also supports variable centers of rotation. During normal operations, the 073 * center of rotation is usually the same as the physical center of the robot; therefore, the 074 * argument is defaulted to that use case. However, if you wish to change the center of rotation 075 * for evasive maneuvers, vision alignment, or for any other use case, you can do so. 076 * 077 * @param chassisSpeeds The desired chassis speed. 078 * @param centerOfRotationMeters The center of rotation. For example, if you set the center of 079 * rotation at one corner of the robot and provide a chassis speed that only has a dtheta 080 * component, the robot will rotate around that corner. 081 * @return An array containing the module states. Use caution because these module states are not 082 * normalized. Sometimes, a user input may cause one of the module speeds to go above the 083 * attainable max velocity. Use the {@link #desaturateWheelSpeeds(SwerveModuleState[], double) 084 * DesaturateWheelSpeeds} function to rectify this issue. 085 */ 086 @SuppressWarnings("LocalVariableName") 087 public SwerveModuleState[] toSwerveModuleStates( 088 ChassisSpeeds chassisSpeeds, Translation2d centerOfRotationMeters) { 089 if (!centerOfRotationMeters.equals(m_prevCoR)) { 090 for (int i = 0; i < m_numModules; i++) { 091 m_inverseKinematics.setRow( 092 i * 2 + 0, 093 0, /* Start Data */ 094 1, 095 0, 096 -m_modules[i].getY() + centerOfRotationMeters.getY()); 097 m_inverseKinematics.setRow( 098 i * 2 + 1, 099 0, /* Start Data */ 100 0, 101 1, 102 +m_modules[i].getX() - centerOfRotationMeters.getX()); 103 } 104 m_prevCoR = centerOfRotationMeters; 105 } 106 107 var chassisSpeedsVector = new SimpleMatrix(3, 1); 108 chassisSpeedsVector.setColumn( 109 0, 110 0, 111 chassisSpeeds.vxMetersPerSecond, 112 chassisSpeeds.vyMetersPerSecond, 113 chassisSpeeds.omegaRadiansPerSecond); 114 115 var moduleStatesMatrix = m_inverseKinematics.mult(chassisSpeedsVector); 116 SwerveModuleState[] moduleStates = new SwerveModuleState[m_numModules]; 117 118 for (int i = 0; i < m_numModules; i++) { 119 double x = moduleStatesMatrix.get(i * 2, 0); 120 double y = moduleStatesMatrix.get(i * 2 + 1, 0); 121 122 double speed = Math.hypot(x, y); 123 Rotation2d angle = new Rotation2d(x, y); 124 125 moduleStates[i] = new SwerveModuleState(speed, angle); 126 } 127 128 return moduleStates; 129 } 130 131 /** 132 * Performs inverse kinematics. See {@link #toSwerveModuleStates(ChassisSpeeds, Translation2d)} 133 * toSwerveModuleStates for more information. 134 * 135 * @param chassisSpeeds The desired chassis speed. 136 * @return An array containing the module states. 137 */ 138 public SwerveModuleState[] toSwerveModuleStates(ChassisSpeeds chassisSpeeds) { 139 return toSwerveModuleStates(chassisSpeeds, new Translation2d()); 140 } 141 142 /** 143 * Performs forward kinematics to return the resulting chassis state from the given module states. 144 * This method is often used for odometry -- determining the robot's position on the field using 145 * data from the real-world speed and angle of each module on the robot. 146 * 147 * @param wheelStates The state of the modules (as a SwerveModuleState type) as measured from 148 * respective encoders and gyros. The order of the swerve module states should be same as 149 * passed into the constructor of this class. 150 * @return The resulting chassis speed. 151 */ 152 public ChassisSpeeds toChassisSpeeds(SwerveModuleState... wheelStates) { 153 if (wheelStates.length != m_numModules) { 154 throw new IllegalArgumentException( 155 "Number of modules is not consistent with number of wheel locations provided in " 156 + "constructor"); 157 } 158 var moduleStatesMatrix = new SimpleMatrix(m_numModules * 2, 1); 159 160 for (int i = 0; i < m_numModules; i++) { 161 var module = wheelStates[i]; 162 moduleStatesMatrix.set(i * 2, 0, module.speedMetersPerSecond * module.angle.getCos()); 163 moduleStatesMatrix.set(i * 2 + 1, module.speedMetersPerSecond * module.angle.getSin()); 164 } 165 166 var chassisSpeedsVector = m_forwardKinematics.mult(moduleStatesMatrix); 167 return new ChassisSpeeds( 168 chassisSpeedsVector.get(0, 0), 169 chassisSpeedsVector.get(1, 0), 170 chassisSpeedsVector.get(2, 0)); 171 } 172 173 /** 174 * Renormalizes the wheel speeds if any individual speed is above the specified maximum. 175 * 176 * <p>Sometimes, after inverse kinematics, the requested speed from one or more modules may be 177 * above the max attainable speed for the driving motor on that module. To fix this issue, one can 178 * reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the 179 * absolute threshold, while maintaining the ratio of speeds between modules. 180 * 181 * @param moduleStates Reference to array of module states. The array will be mutated with the 182 * normalized speeds! 183 * @param attainableMaxSpeedMetersPerSecond The absolute max speed that a module can reach. 184 */ 185 public static void desaturateWheelSpeeds( 186 SwerveModuleState[] moduleStates, double attainableMaxSpeedMetersPerSecond) { 187 double realMaxSpeed = Collections.max(Arrays.asList(moduleStates)).speedMetersPerSecond; 188 if (realMaxSpeed > attainableMaxSpeedMetersPerSecond) { 189 for (SwerveModuleState moduleState : moduleStates) { 190 moduleState.speedMetersPerSecond = 191 moduleState.speedMetersPerSecond / realMaxSpeed * attainableMaxSpeedMetersPerSecond; 192 } 193 } 194 } 195}