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 org.wpilib.math.kinematics; 006 007import static org.wpilib.units.Units.MetersPerSecond; 008import static org.wpilib.units.Units.RadiansPerSecond; 009 010import java.util.Arrays; 011import org.ejml.simple.SimpleMatrix; 012import org.wpilib.math.geometry.Rotation2d; 013import org.wpilib.math.geometry.Translation2d; 014import org.wpilib.math.geometry.Twist2d; 015import org.wpilib.math.kinematics.proto.SwerveDriveKinematicsProto; 016import org.wpilib.math.kinematics.struct.SwerveDriveKinematicsStruct; 017import org.wpilib.math.util.MathSharedStore; 018import org.wpilib.units.measure.AngularVelocity; 019import org.wpilib.units.measure.LinearVelocity; 020import org.wpilib.util.protobuf.ProtobufSerializable; 021import org.wpilib.util.struct.Struct; 022import org.wpilib.util.struct.StructSerializable; 023 024/** 025 * Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual 026 * module states (velocity and angle). 027 * 028 * <p>The inverse kinematics (converting from a desired chassis velocity to individual module 029 * states) uses the relative locations of the modules with respect to the center of rotation. The 030 * center of rotation for inverse kinematics is also variable. This means that you can set your 031 * center of rotation in a corner of the robot to perform special evasion maneuvers. 032 * 033 * <p>Forward kinematics (converting an array of module states into the overall chassis motion) is 034 * performs the exact opposite of what inverse kinematics does. Since this is an overdetermined 035 * system (more equations than variables), we use a least-squares approximation. 036 * 037 * <p>The inverse kinematics: [moduleVelocities] = [moduleLocations] * [chassisVelocities] We take 038 * the Moore-Penrose pseudoinverse of [moduleLocations] and then multiply by [moduleVelocities] to 039 * get our chassis velocities. 040 * 041 * <p>Forward kinematics is also used for odometry -- determining the position of the robot on the 042 * field using encoders and a gyro. 043 */ 044@SuppressWarnings("overrides") 045public class SwerveDriveKinematics 046 implements Kinematics< 047 SwerveModulePosition[], SwerveModuleVelocity[], SwerveModuleAcceleration[]>, 048 ProtobufSerializable, 049 StructSerializable { 050 private final SimpleMatrix m_firstOrderInverseKinematics; 051 private final SimpleMatrix m_firstOrderForwardKinematics; 052 private final SimpleMatrix m_secondOrderInverseKinematics; 053 private final SimpleMatrix m_secondOrderForwardKinematics; 054 055 private final int m_numModules; 056 private final Translation2d[] m_modules; 057 private Rotation2d[] m_moduleHeadings; 058 private Translation2d m_prevCoR = Translation2d.kZero; 059 060 /** 061 * Constructs a swerve drive kinematics object. This takes in a variable number of module 062 * locations as Translation2d objects. The order in which you pass in the module locations is the 063 * same order that you will receive the module states when performing inverse kinematics. It is 064 * also expected that you pass in the module states in the same order when calling the forward 065 * kinematics methods. 066 * 067 * @param moduleTranslations The locations of the modules relative to the physical center of the 068 * robot. 069 */ 070 public SwerveDriveKinematics(Translation2d... moduleTranslations) { 071 if (moduleTranslations.length < 2) { 072 throw new IllegalArgumentException("A swerve drive requires at least two modules"); 073 } 074 m_numModules = moduleTranslations.length; 075 m_modules = Arrays.copyOf(moduleTranslations, m_numModules); 076 m_moduleHeadings = new Rotation2d[m_numModules]; 077 Arrays.fill(m_moduleHeadings, Rotation2d.kZero); 078 m_firstOrderInverseKinematics = new SimpleMatrix(m_numModules * 2, 3); 079 m_secondOrderInverseKinematics = new SimpleMatrix(m_numModules * 2, 4); 080 081 setInverseKinematics(Translation2d.kZero); 082 083 m_firstOrderForwardKinematics = m_firstOrderInverseKinematics.pseudoInverse(); 084 m_secondOrderForwardKinematics = m_secondOrderInverseKinematics.pseudoInverse(); 085 086 MathSharedStore.reportUsage("SwerveDriveKinematics", ""); 087 } 088 089 /** 090 * Reset the internal swerve module headings. 091 * 092 * @param moduleHeadings The swerve module headings. The order of the module headings should be 093 * same as passed into the constructor of this class. 094 */ 095 public void resetHeadings(Rotation2d... moduleHeadings) { 096 if (moduleHeadings.length != m_numModules) { 097 throw new IllegalArgumentException( 098 "Number of headings is not consistent with number of module locations provided in " 099 + "constructor"); 100 } 101 m_moduleHeadings = Arrays.copyOf(moduleHeadings, m_numModules); 102 } 103 104 /** 105 * Performs inverse kinematics to return the module states from a desired chassis velocity. This 106 * method is often used to convert joystick values into module velocities and angles. 107 * 108 * <p>This function also supports variable centers of rotation. During normal operations, the 109 * center of rotation is usually the same as the physical center of the robot; therefore, the 110 * argument is defaulted to that use case. However, if you wish to change the center of rotation 111 * for evasive maneuvers, vision alignment, or for any other use case, you can do so. 112 * 113 * <p>In the case that the desired chassis velocities are zero (i.e. the robot will be 114 * stationary), the previously calculated module angle will be maintained. 115 * 116 * @param chassisVelocities The desired chassis velocity. 117 * @param centerOfRotation The center of rotation. For example, if you set the center of rotation 118 * at one corner of the robot and provide a chassis velocity that only has a dtheta component, 119 * the robot will rotate around that corner. 120 * @return An array containing the module states. Use caution because these module states are not 121 * normalized. Sometimes, a user input may cause one of the module velocities to go above the 122 * attainable max velocity. Use the {@link #desaturateWheelVelocities(SwerveModuleVelocity[], 123 * double) DesaturateWheelVelocities} function to rectify this issue. 124 */ 125 public SwerveModuleVelocity[] toSwerveModuleVelocities( 126 ChassisVelocities chassisVelocities, Translation2d centerOfRotation) { 127 var moduleVelocities = new SwerveModuleVelocity[m_numModules]; 128 129 if (chassisVelocities.vx == 0.0 130 && chassisVelocities.vy == 0.0 131 && chassisVelocities.omega == 0.0) { 132 for (int i = 0; i < m_numModules; i++) { 133 moduleVelocities[i] = new SwerveModuleVelocity(0.0, m_moduleHeadings[i]); 134 } 135 136 return moduleVelocities; 137 } 138 139 if (!centerOfRotation.equals(m_prevCoR)) { 140 setInverseKinematics(centerOfRotation); 141 } 142 143 var chassisVelocitiesVector = new SimpleMatrix(3, 1); 144 chassisVelocitiesVector.setColumn( 145 0, 0, chassisVelocities.vx, chassisVelocities.vy, chassisVelocities.omega); 146 147 var moduleVelocitiesMatrix = m_firstOrderInverseKinematics.mult(chassisVelocitiesVector); 148 149 for (int i = 0; i < m_numModules; i++) { 150 double x = moduleVelocitiesMatrix.get(i * 2, 0); 151 double y = moduleVelocitiesMatrix.get(i * 2 + 1, 0); 152 153 double velocity = Math.hypot(x, y); 154 Rotation2d angle = velocity > 1e-6 ? new Rotation2d(x, y) : m_moduleHeadings[i]; 155 156 moduleVelocities[i] = new SwerveModuleVelocity(velocity, angle); 157 m_moduleHeadings[i] = angle; 158 } 159 160 return moduleVelocities; 161 } 162 163 /** 164 * Performs inverse kinematics. See {@link #toSwerveModuleVelocities(ChassisVelocities, 165 * Translation2d)} toSwerveModuleVelocities for more information. 166 * 167 * @param chassisVelocities The desired chassis velocity. 168 * @return An array containing the module states. 169 */ 170 public SwerveModuleVelocity[] toSwerveModuleVelocities(ChassisVelocities chassisVelocities) { 171 return toSwerveModuleVelocities(chassisVelocities, Translation2d.kZero); 172 } 173 174 @Override 175 public SwerveModuleVelocity[] toWheelVelocities(ChassisVelocities chassisVelocities) { 176 return toSwerveModuleVelocities(chassisVelocities); 177 } 178 179 /** 180 * Performs forward kinematics to return the resulting chassis state from the given module states. 181 * This method is often used for odometry -- determining the robot's position on the field using 182 * data from the real-world velocity and angle of each module on the robot. 183 * 184 * @param moduleVelocities The state of the modules (as a SwerveModuleVelocity type) as measured 185 * from respective encoders and gyros. The order of the swerve module states should be same as 186 * passed into the constructor of this class. 187 * @return The resulting chassis velocity. 188 */ 189 @Override 190 public ChassisVelocities toChassisVelocities(SwerveModuleVelocity... moduleVelocities) { 191 if (moduleVelocities.length != m_numModules) { 192 throw new IllegalArgumentException( 193 "Number of modules is not consistent with number of module locations provided in " 194 + "constructor"); 195 } 196 var moduleVelocitiesMatrix = new SimpleMatrix(m_numModules * 2, 1); 197 198 for (int i = 0; i < m_numModules; i++) { 199 var module = moduleVelocities[i]; 200 moduleVelocitiesMatrix.set(i * 2, 0, module.velocity * module.angle.getCos()); 201 moduleVelocitiesMatrix.set(i * 2 + 1, module.velocity * module.angle.getSin()); 202 } 203 204 var chassisVelocitiesVector = m_firstOrderForwardKinematics.mult(moduleVelocitiesMatrix); 205 return new ChassisVelocities( 206 chassisVelocitiesVector.get(0, 0), 207 chassisVelocitiesVector.get(1, 0), 208 chassisVelocitiesVector.get(2, 0)); 209 } 210 211 /** 212 * Performs forward kinematics to return the resulting chassis state from the given module states. 213 * This method is often used for odometry -- determining the robot's position on the field using 214 * data from the real-world velocity and angle of each module on the robot. 215 * 216 * @param moduleDeltas The latest change in position of the modules (as a SwerveModulePosition 217 * type) as measured from respective encoders and gyros. The order of the swerve module states 218 * should be same as passed into the constructor of this class. 219 * @return The resulting Twist2d. 220 */ 221 public Twist2d toTwist2d(SwerveModulePosition... moduleDeltas) { 222 if (moduleDeltas.length != m_numModules) { 223 throw new IllegalArgumentException( 224 "Number of modules is not consistent with number of module locations provided in " 225 + "constructor"); 226 } 227 var moduleDeltaMatrix = new SimpleMatrix(m_numModules * 2, 1); 228 229 for (int i = 0; i < m_numModules; i++) { 230 var module = moduleDeltas[i]; 231 moduleDeltaMatrix.set(i * 2, 0, module.distance * module.angle.getCos()); 232 moduleDeltaMatrix.set(i * 2 + 1, 0, module.distance * module.angle.getSin()); 233 } 234 235 var chassisDeltaVector = m_firstOrderForwardKinematics.mult(moduleDeltaMatrix); 236 return new Twist2d( 237 chassisDeltaVector.get(0, 0), chassisDeltaVector.get(1, 0), chassisDeltaVector.get(2, 0)); 238 } 239 240 @Override 241 public Twist2d toTwist2d(SwerveModulePosition[] start, SwerveModulePosition[] end) { 242 if (start.length != end.length) { 243 throw new IllegalArgumentException("Inconsistent number of modules!"); 244 } 245 var newPositions = new SwerveModulePosition[start.length]; 246 for (int i = 0; i < start.length; i++) { 247 newPositions[i] = new SwerveModulePosition(end[i].distance - start[i].distance, end[i].angle); 248 } 249 return toTwist2d(newPositions); 250 } 251 252 /** 253 * Renormalizes the wheel velocities if any individual velocity is above the specified maximum. 254 * 255 * <p>Sometimes, after inverse kinematics, the requested velocity from one or more modules may be 256 * above the max attainable velocity for the driving motor on that module. To fix this issue, one 257 * can reduce all the wheel velocities to make sure that all requested module velocities are 258 * at-or-below the absolute threshold, while maintaining the ratio of velocities between modules. 259 * 260 * <p>Scaling down the module velocities rotates the direction of net motion in the opposite 261 * direction of rotational velocity, which makes discretizing the chassis velocities inaccurate 262 * because the discretization did not account for this translational skew. 263 * 264 * @param moduleVelocities Reference to array of module states. The array will be mutated with the 265 * normalized velocities! 266 * @param attainableMaxVelocity The absolute max velocity in meters per second that a module can 267 * reach. 268 */ 269 public static void desaturateWheelVelocities( 270 SwerveModuleVelocity[] moduleVelocities, double attainableMaxVelocity) { 271 double realMaxVelocity = 0; 272 for (SwerveModuleVelocity moduleVelocity : moduleVelocities) { 273 realMaxVelocity = Math.max(realMaxVelocity, Math.abs(moduleVelocity.velocity)); 274 } 275 if (realMaxVelocity > attainableMaxVelocity) { 276 for (SwerveModuleVelocity moduleVelocity : moduleVelocities) { 277 moduleVelocity.velocity = moduleVelocity.velocity / realMaxVelocity * attainableMaxVelocity; 278 } 279 } 280 } 281 282 /** 283 * Renormalizes the wheel velocities if any individual velocity is above the specified maximum. 284 * 285 * <p>Sometimes, after inverse kinematics, the requested velocity from one or more modules may be 286 * above the max attainable velocity for the driving motor on that module. To fix this issue, one 287 * can reduce all the wheel velocities to make sure that all requested module velocities are 288 * at-or-below the absolute threshold, while maintaining the ratio of velocities between modules. 289 * 290 * <p>Scaling down the module velocities rotates the direction of net motion in the opposite 291 * direction of rotational velocity, which makes discretizing the chassis velocities inaccurate 292 * because the discretization did not account for this translational skew. 293 * 294 * @param moduleVelocities Reference to array of module states. The array will be mutated with the 295 * normalized velocities! 296 * @param attainableMaxVelocity The absolute max velocity in meters per second that a module can 297 * reach. 298 */ 299 public static void desaturateWheelVelocities( 300 SwerveModuleVelocity[] moduleVelocities, LinearVelocity attainableMaxVelocity) { 301 desaturateWheelVelocities(moduleVelocities, attainableMaxVelocity.in(MetersPerSecond)); 302 } 303 304 /** 305 * Renormalizes the wheel velocities if any individual velocity is above the specified maximum, as 306 * well as getting rid of joystick saturation at edges of joystick. 307 * 308 * <p>Sometimes, after inverse kinematics, the requested velocity from one or more modules may be 309 * above the max attainable velocity for the driving motor on that module. To fix this issue, one 310 * can reduce all the wheel velocities to make sure that all requested module velocities are 311 * at-or-below the absolute threshold, while maintaining the ratio of velocities between modules. 312 * 313 * <p>Scaling down the module velocities rotates the direction of net motion in the opposite 314 * direction of rotational velocity, which makes discretizing the chassis velocities inaccurate 315 * because the discretization did not account for this translational skew. 316 * 317 * @param moduleVelocities Reference to array of module states. The array will be mutated with the 318 * normalized velocities! 319 * @param desiredChassisVelocity The desired velocity of the robot 320 * @param attainableMaxModuleVelocity The absolute max velocity in meters per second that a module 321 * can reach 322 * @param attainableMaxTranslationalVelocity The absolute max velocity in meters per second that 323 * your robot can reach while translating 324 * @param attainableMaxRotationalVelocity The absolute max velocity in radians per second the 325 * robot can reach while rotating 326 */ 327 public static void desaturateWheelVelocities( 328 SwerveModuleVelocity[] moduleVelocities, 329 ChassisVelocities desiredChassisVelocity, 330 double attainableMaxModuleVelocity, 331 double attainableMaxTranslationalVelocity, 332 double attainableMaxRotationalVelocity) { 333 double realMaxVelocity = 0; 334 for (SwerveModuleVelocity moduleVelocity : moduleVelocities) { 335 realMaxVelocity = Math.max(realMaxVelocity, Math.abs(moduleVelocity.velocity)); 336 } 337 338 if (attainableMaxTranslationalVelocity == 0 339 || attainableMaxRotationalVelocity == 0 340 || realMaxVelocity == 0) { 341 return; 342 } 343 double translationalK = 344 Math.hypot(desiredChassisVelocity.vx, desiredChassisVelocity.vy) 345 / attainableMaxTranslationalVelocity; 346 double rotationalK = Math.abs(desiredChassisVelocity.omega) / attainableMaxRotationalVelocity; 347 double k = Math.max(translationalK, rotationalK); 348 double scale = Math.min(k * attainableMaxModuleVelocity / realMaxVelocity, 1); 349 for (SwerveModuleVelocity moduleVelocity : moduleVelocities) { 350 moduleVelocity.velocity *= scale; 351 } 352 } 353 354 /** 355 * Renormalizes the wheel velocities if any individual velocity is above the specified maximum, as 356 * well as getting rid of joystick saturation at edges of joystick. 357 * 358 * <p>Sometimes, after inverse kinematics, the requested velocity from one or more modules may be 359 * above the max attainable velocity for the driving motor on that module. To fix this issue, one 360 * can reduce all the wheel velocities to make sure that all requested module velocities are 361 * at-or-below the absolute threshold, while maintaining the ratio of velocities between modules. 362 * 363 * <p>Scaling down the module velocities rotates the direction of net motion in the opposite 364 * direction of rotational velocity, which makes discretizing the chassis velocities inaccurate 365 * because the discretization did not account for this translational skew. 366 * 367 * @param moduleVelocities Reference to array of module states. The array will be mutated with the 368 * normalized velocities! 369 * @param desiredChassisVelocity The desired velocity of the robot 370 * @param attainableMaxModuleVelocity The absolute max velocity that a module can reach 371 * @param attainableMaxTranslationalVelocity The absolute max velocity that your robot can reach 372 * while translating 373 * @param attainableMaxRotationalVelocity The absolute max velocity the robot can reach while 374 * rotating 375 */ 376 public static void desaturateWheelVelocities( 377 SwerveModuleVelocity[] moduleVelocities, 378 ChassisVelocities desiredChassisVelocity, 379 LinearVelocity attainableMaxModuleVelocity, 380 LinearVelocity attainableMaxTranslationalVelocity, 381 AngularVelocity attainableMaxRotationalVelocity) { 382 desaturateWheelVelocities( 383 moduleVelocities, 384 desiredChassisVelocity, 385 attainableMaxModuleVelocity.in(MetersPerSecond), 386 attainableMaxTranslationalVelocity.in(MetersPerSecond), 387 attainableMaxRotationalVelocity.in(RadiansPerSecond)); 388 } 389 390 @Override 391 public SwerveModulePosition[] copy(SwerveModulePosition[] positions) { 392 var newPositions = new SwerveModulePosition[positions.length]; 393 for (int i = 0; i < positions.length; ++i) { 394 newPositions[i] = positions[i].copy(); 395 } 396 return newPositions; 397 } 398 399 @Override 400 public void copyInto(SwerveModulePosition[] positions, SwerveModulePosition[] output) { 401 if (positions.length != output.length) { 402 throw new IllegalArgumentException("Inconsistent number of modules!"); 403 } 404 for (int i = 0; i < positions.length; ++i) { 405 output[i].distance = positions[i].distance; 406 output[i].angle = positions[i].angle; 407 } 408 } 409 410 @Override 411 public SwerveModulePosition[] interpolate( 412 SwerveModulePosition[] startValue, SwerveModulePosition[] endValue, double t) { 413 if (endValue.length != startValue.length) { 414 throw new IllegalArgumentException("Inconsistent number of modules!"); 415 } 416 var newPositions = new SwerveModulePosition[startValue.length]; 417 for (int i = 0; i < startValue.length; ++i) { 418 newPositions[i] = startValue[i].interpolate(endValue[i], t); 419 } 420 return newPositions; 421 } 422 423 /** 424 * Gets the locations of the modules relative to the center of rotation. 425 * 426 * @return The locations of the modules relative to the center of rotation. This array should not 427 * be modified. 428 */ 429 @SuppressWarnings("PMD.MethodReturnsInternalArray") 430 public Translation2d[] getModules() { 431 return m_modules; 432 } 433 434 /** SwerveDriveKinematics protobuf for serialization. */ 435 public static final SwerveDriveKinematicsProto proto = new SwerveDriveKinematicsProto(); 436 437 /** 438 * Creates an implementation of the {@link Struct} interface for swerve drive kinematics objects. 439 * 440 * @param numModules The number of modules of the kinematics objects this serializer processes. 441 * @return The struct implementation. 442 */ 443 public static final SwerveDriveKinematicsStruct getStruct(int numModules) { 444 return new SwerveDriveKinematicsStruct(numModules); 445 } 446 447 /** 448 * Performs inverse kinematics to return the module accelerations from a desired chassis 449 * acceleration. This method is often used for dynamics calculations -- converting desired robot 450 * accelerations into individual module accelerations. 451 * 452 * <p>This function also supports variable centers of rotation. During normal operations, the 453 * center of rotation is usually the same as the physical center of the robot; therefore, the 454 * argument is defaulted to that use case. However, if you wish to change the center of rotation 455 * for evasive maneuvers, vision alignment, or for any other use case, you can do so. 456 * 457 * @param chassisAccelerations The desired chassis accelerations. 458 * @param angularVelocity The desired robot angular velocity. 459 * @param centerOfRotation The center of rotation. For example, if you set the center of rotation 460 * at one corner of the robot and provide a chassis acceleration that only has a dtheta 461 * component, the robot will rotate around that corner. 462 * @return An array containing the module accelerations. 463 */ 464 public SwerveModuleAcceleration[] toSwerveModuleAccelerations( 465 ChassisAccelerations chassisAccelerations, 466 double angularVelocity, 467 Translation2d centerOfRotation) { 468 // Derivation for second-order kinematics from "Swerve Drive Second Order Kinematics" 469 // by FRC Team 449 - The Blair Robot Project, Rafi Pedersen 470 // https://www.chiefdelphi.com/uploads/short-url/qzj4k2LyBs7rLxAem0YajNIlStH.pdf 471 472 var moduleAccelerations = new SwerveModuleAcceleration[m_numModules]; 473 474 if (chassisAccelerations.ax == 0.0 475 && chassisAccelerations.ay == 0.0 476 && chassisAccelerations.alpha == 0.0) { 477 for (int i = 0; i < m_numModules; i++) { 478 moduleAccelerations[i] = new SwerveModuleAcceleration(0.0, Rotation2d.kZero); 479 } 480 return moduleAccelerations; 481 } 482 483 if (!centerOfRotation.equals(m_prevCoR)) { 484 setInverseKinematics(centerOfRotation); 485 } 486 487 var chassisAccelerationsVector = new SimpleMatrix(4, 1); 488 chassisAccelerationsVector.setColumn( 489 0, 490 0, 491 chassisAccelerations.ax, 492 chassisAccelerations.ay, 493 angularVelocity * angularVelocity, 494 chassisAccelerations.alpha); 495 496 var moduleAccelerationsMatrix = m_secondOrderInverseKinematics.mult(chassisAccelerationsVector); 497 498 for (int i = 0; i < m_numModules; i++) { 499 double x = moduleAccelerationsMatrix.get(i * 2, 0); 500 double y = moduleAccelerationsMatrix.get(i * 2 + 1, 0); 501 502 // For swerve modules, we need to compute both linear acceleration and angular acceleration 503 // The linear acceleration is the magnitude of the acceleration vector 504 double linearAcceleration = Math.hypot(x, y); 505 506 if (linearAcceleration <= 1e-6) { 507 moduleAccelerations[i] = new SwerveModuleAcceleration(linearAcceleration, Rotation2d.kZero); 508 } else { 509 moduleAccelerations[i] = 510 new SwerveModuleAcceleration(linearAcceleration, new Rotation2d(x, y)); 511 } 512 } 513 514 return moduleAccelerations; 515 } 516 517 /** 518 * Performs inverse kinematics. See {@link #toSwerveModuleAccelerations(ChassisAccelerations, 519 * double, Translation2d)} toSwerveModuleAccelerations for more information. 520 * 521 * @param chassisAccelerations The desired chassis accelerations. 522 * @param angularVelocity The desired robot angular velocity. 523 * @return An array containing the module accelerations. 524 */ 525 public SwerveModuleAcceleration[] toSwerveModuleAccelerations( 526 ChassisAccelerations chassisAccelerations, double angularVelocity) { 527 return toSwerveModuleAccelerations(chassisAccelerations, angularVelocity, Translation2d.kZero); 528 } 529 530 @Override 531 public SwerveModuleAcceleration[] toWheelAccelerations( 532 ChassisAccelerations chassisAccelerations) { 533 return toSwerveModuleAccelerations(chassisAccelerations, 0.0); 534 } 535 536 /** 537 * Performs forward kinematics to return the resulting chassis accelerations from the given module 538 * accelerations. This method is often used for dynamics calculations -- determining the robot's 539 * acceleration on the field using data from the real-world acceleration of each module on the 540 * robot. 541 * 542 * @param moduleAccelerations The accelerations of the modules as measured from respective 543 * encoders and gyros. The order of the swerve module accelerations should be same as passed 544 * into the constructor of this class. 545 * @return The resulting chassis accelerations. 546 */ 547 @Override 548 public ChassisAccelerations toChassisAccelerations( 549 SwerveModuleAcceleration... moduleAccelerations) { 550 // Derivation for second-order kinematics from "Swerve Drive Second Order Kinematics" 551 // by FRC Team 449 - The Blair Robot Project, Rafi Pedersen 552 // https://www.chiefdelphi.com/uploads/short-url/qzj4k2LyBs7rLxAem0YajNIlStH.pdf 553 554 if (moduleAccelerations.length != m_numModules) { 555 throw new IllegalArgumentException( 556 "Number of modules is not consistent with number of module locations provided in " 557 + "constructor"); 558 } 559 var moduleAccelerationsMatrix = new SimpleMatrix(m_numModules * 2, 1); 560 561 for (int i = 0; i < m_numModules; i++) { 562 var module = moduleAccelerations[i]; 563 564 moduleAccelerationsMatrix.set(i * 2 + 0, 0, module.acceleration * module.angle.getCos()); 565 moduleAccelerationsMatrix.set(i * 2 + 1, 0, module.acceleration * module.angle.getSin()); 566 } 567 568 var chassisAccelerationsVector = m_secondOrderForwardKinematics.mult(moduleAccelerationsMatrix); 569 570 // the second order kinematics equation for swerve drive yields a state vector [aₓ, a_y, ω², α] 571 return new ChassisAccelerations( 572 chassisAccelerationsVector.get(0, 0), 573 chassisAccelerationsVector.get(1, 0), 574 chassisAccelerationsVector.get(3, 0)); 575 } 576 577 /** 578 * Sets both inverse kinematics matrices based on the new center of rotation. This does not check 579 * if the new center of rotation is different from the previous one, so a check should be included 580 * before the call to this function. 581 * 582 * @param centerOfRotation new center of rotation 583 */ 584 private void setInverseKinematics(Translation2d centerOfRotation) { 585 for (int i = 0; i < m_numModules; i++) { 586 var rx = m_modules[i].getX() - centerOfRotation.getX(); 587 var ry = m_modules[i].getY() - centerOfRotation.getY(); 588 589 m_firstOrderInverseKinematics.setRow(i * 2 + 0, 0, /* Start Data */ 1, 0, -ry); 590 m_firstOrderInverseKinematics.setRow(i * 2 + 1, 0, /* Start Data */ 0, 1, rx); 591 592 m_secondOrderInverseKinematics.setRow(i * 2 + 0, 0, /* Start Data */ 1, 0, -rx, -ry); 593 m_secondOrderInverseKinematics.setRow(i * 2 + 1, 0, /* Start Data */ 0, 1, -ry, +rx); 594 } 595 m_prevCoR = centerOfRotation; 596 } 597}