Class MecanumDriveKinematics

java.lang.Object
edu.wpi.first.math.kinematics.MecanumDriveKinematics

public class MecanumDriveKinematics
extends Object
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel speeds.

The inverse kinematics (converting from a desired chassis velocity to individual wheel speeds) uses the relative locations of the wheels 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 wheel speeds 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: [wheelSpeeds] = [wheelLocations] * [chassisSpeeds] We take the Moore-Penrose pseudoinverse of [wheelLocations] and then multiply by [wheelSpeeds] 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

    • MecanumDriveKinematics

      public MecanumDriveKinematics​(Translation2d frontLeftWheelMeters, Translation2d frontRightWheelMeters, Translation2d rearLeftWheelMeters, Translation2d rearRightWheelMeters)
      Constructs a mecanum drive kinematics object.
      Parameters:
      frontLeftWheelMeters - The location of the front-left wheel relative to the physical center of the robot.
      frontRightWheelMeters - The location of the front-right wheel relative to the physical center of the robot.
      rearLeftWheelMeters - The location of the rear-left wheel relative to the physical center of the robot.
      rearRightWheelMeters - The location of the rear-right wheel relative to the physical center of the robot.
  • Method Details

    • toWheelSpeeds

      public MecanumDriveWheelSpeeds toWheelSpeeds​(ChassisSpeeds chassisSpeeds, Translation2d centerOfRotationMeters)
      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.

      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.

      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:
      The wheel speeds. Use caution because they are not normalized. Sometimes, a user input may cause one of the wheel speeds to go above the attainable max velocity. Use the MecanumDriveWheelSpeeds.desaturate(double) function to rectify this issue.
    • toWheelSpeeds

      Performs inverse kinematics. See toWheelSpeeds(ChassisSpeeds, Translation2d) for more information.
      Parameters:
      chassisSpeeds - The desired chassis speed.
      Returns:
      The wheel speeds.
    • toChassisSpeeds

      Performs forward kinematics to return the resulting chassis state from the given 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.
      Parameters:
      wheelSpeeds - The current mecanum drive wheel speeds.
      Returns:
      The resulting chassis speed.
    • toTwist2d

      public Twist2d toTwist2d​(MecanumDriveWheelPositions wheelDeltas)
      Performs forward kinematics to return the resulting Twist2d 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.
      Parameters:
      wheelDeltas - The distances driven by each wheel.
      Returns:
      The resulting Twist2d.