Class SwerveDriveKinematics

java.lang.Object
edu.wpi.first.math.kinematics.SwerveDriveKinematics
All Implemented Interfaces:
Kinematics<SwerveDriveKinematics.SwerveDriveWheelStates,​SwerveDriveWheelPositions>

public class SwerveDriveKinematics
extends Object
implements Kinematics<SwerveDriveKinematics.SwerveDriveWheelStates,​SwerveDriveWheelPositions>
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states (speed and angle).

The inverse kinematics (converting from a desired chassis velocity to individual module states) uses the relative locations of the modules with respect to the center of rotation. The center of rotation for inverse kinematics is also variable. This means that you can set your center of rotation in a corner of the robot to perform special evasion maneuvers.

Forward kinematics (converting an array of module states into the overall chassis motion) is performs the exact opposite of what inverse kinematics does. Since this is an overdetermined system (more equations than variables), we use a least-squares approximation.

The inverse kinematics: [moduleStates] = [moduleLocations] * [chassisSpeeds] We take the Moore-Penrose pseudoinverse of [moduleLocations] and then multiply by [moduleStates] to get our chassis speeds.

Forward kinematics is also used for odometry -- determining the position of the robot on the field using encoders and a gyro.

  • Constructor Details

    • SwerveDriveKinematics

      public SwerveDriveKinematics​(Translation2d... moduleTranslationsMeters)
      Constructs a swerve drive kinematics object. This takes in a variable number of module locations as Translation2d objects. The order in which you pass in the module locations is the same order that you will receive the module states when performing inverse kinematics. It is also expected that you pass in the module states in the same order when calling the forward kinematics methods.
      Parameters:
      moduleTranslationsMeters - The locations of the modules relative to the physical center of the robot.
  • Method Details

    • resetHeadings

      public void resetHeadings​(Rotation2d... moduleHeadings)
      Reset the internal swerve module headings.
      Parameters:
      moduleHeadings - The swerve module headings. The order of the module headings should be same as passed into the constructor of this class.
    • toSwerveModuleStates

      public SwerveModuleState[] toSwerveModuleStates​(ChassisSpeeds chassisSpeeds, Translation2d centerOfRotationMeters)
      Performs inverse kinematics to return the module states from a desired chassis velocity. This method is often used to convert joystick values into module speeds and angles.

      This function also supports variable centers of rotation. During normal operations, the center of rotation is usually the same as the physical center of the robot; therefore, the argument is defaulted to that use case. However, if you wish to change the center of rotation for evasive maneuvers, vision alignment, or for any other use case, you can do so.

      In the case that the desired chassis speeds are zero (i.e. the robot will be stationary), the previously calculated module angle will be maintained.

      Parameters:
      chassisSpeeds - The desired chassis speed.
      centerOfRotationMeters - The center of rotation. For example, if you set the center of rotation at one corner of the robot and provide a chassis speed that only has a dtheta component, the robot will rotate around that corner.
      Returns:
      An array containing the module states. Use caution because these module states are not normalized. Sometimes, a user input may cause one of the module speeds to go above the attainable max velocity. Use the DesaturateWheelSpeeds function to rectify this issue.
    • toSwerveModuleStates

      Performs inverse kinematics. See toSwerveModuleStates(ChassisSpeeds, Translation2d) toSwerveModuleStates for more information.
      Parameters:
      chassisSpeeds - The desired chassis speed.
      Returns:
      An array containing the module states.
    • toWheelSpeeds

      Description copied from interface: Kinematics
      Performs inverse kinematics to return the wheel speeds from a desired chassis velocity. This method is often used to convert joystick values into wheel speeds.
      Specified by:
      toWheelSpeeds in interface Kinematics<SwerveDriveKinematics.SwerveDriveWheelStates,​SwerveDriveWheelPositions>
      Parameters:
      chassisSpeeds - The desired chassis speed.
      Returns:
      The wheel speeds.
    • toChassisSpeeds

      public ChassisSpeeds toChassisSpeeds​(SwerveModuleState... moduleStates)
      Performs forward kinematics to return the resulting chassis state from the given module states. This method is often used for odometry -- determining the robot's position on the field using data from the real-world speed and angle of each module on the robot.
      Parameters:
      moduleStates - The state of the modules (as a SwerveModuleState type) as measured from respective encoders and gyros. The order of the swerve module states should be same as passed into the constructor of this class.
      Returns:
      The resulting chassis speed.
    • toChassisSpeeds

      Description copied from interface: Kinematics
      Performs forward kinematics to return the resulting chassis speed from the wheel speeds. This method is often used for odometry -- determining the robot's position on the field using data from the real-world speed of each wheel on the robot.
      Specified by:
      toChassisSpeeds in interface Kinematics<SwerveDriveKinematics.SwerveDriveWheelStates,​SwerveDriveWheelPositions>
      Parameters:
      wheelStates - The speeds of the wheels.
      Returns:
      The chassis speed.
    • toTwist2d

      public Twist2d toTwist2d​(SwerveModulePosition... moduleDeltas)
      Performs forward kinematics to return the resulting chassis state from the given module states. This method is often used for odometry -- determining the robot's position on the field using data from the real-world speed and angle of each module on the robot.
      Parameters:
      moduleDeltas - The latest change in position of the modules (as a SwerveModulePosition type) as measured from respective encoders and gyros. The order of the swerve module states should be same as passed into the constructor of this class.
      Returns:
      The resulting Twist2d.
    • toTwist2d

      public Twist2d toTwist2d​(SwerveDriveWheelPositions wheelDeltas)
      Description copied from interface: Kinematics
      Performs forward kinematics to return the resulting from the given wheel deltas. This method is often used for odometry -- determining the robot's position on the field using changes in the distance driven by each wheel on the robot.
      Specified by:
      toTwist2d in interface Kinematics<SwerveDriveKinematics.SwerveDriveWheelStates,​SwerveDriveWheelPositions>
      Parameters:
      wheelDeltas - The distances driven by each wheel.
      Returns:
      The resulting Twist2d in the robot's movement.
    • desaturateWheelSpeeds

      public static void desaturateWheelSpeeds​(SwerveModuleState[] moduleStates, double attainableMaxSpeedMetersPerSecond)
      Renormalizes the wheel speeds if any individual speed is above the specified maximum.

      Sometimes, after inverse kinematics, the requested speed from one or more modules may be above the max attainable speed for the driving motor on that module. To fix this issue, one can reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the absolute threshold, while maintaining the ratio of speeds between modules.

      Parameters:
      moduleStates - Reference to array of module states. The array will be mutated with the normalized speeds!
      attainableMaxSpeedMetersPerSecond - The absolute max speed that a module can reach.
    • desaturateWheelSpeeds

      public static void desaturateWheelSpeeds​(SwerveModuleState[] moduleStates, ChassisSpeeds desiredChassisSpeed, double attainableMaxModuleSpeedMetersPerSecond, double attainableMaxTranslationalSpeedMetersPerSecond, double attainableMaxRotationalVelocityRadiansPerSecond)
      Renormalizes the wheel speeds if any individual speed is above the specified maximum, as well as getting rid of joystick saturation at edges of joystick.

      Sometimes, after inverse kinematics, the requested speed from one or more modules may be above the max attainable speed for the driving motor on that module. To fix this issue, one can reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the absolute threshold, while maintaining the ratio of speeds between modules.

      Parameters:
      moduleStates - Reference to array of module states. The array will be mutated with the normalized speeds!
      desiredChassisSpeed - The desired speed of the robot
      attainableMaxModuleSpeedMetersPerSecond - The absolute max speed that a module can reach
      attainableMaxTranslationalSpeedMetersPerSecond - The absolute max speed that your robot can reach while translating
      attainableMaxRotationalVelocityRadiansPerSecond - The absolute max speed the robot can reach while rotating