Class DifferentialDriveKinematics

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

public class DifferentialDriveKinematics
extends Object
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velocities for a differential drive.

Inverse kinematics converts a desired chassis speed into left and right velocity components whereas forward kinematics converts left and right component velocities into a linear and angular chassis speed.

  • Field Details

  • Constructor Details

    • DifferentialDriveKinematics

      public DifferentialDriveKinematics​(double trackWidthMeters)
      Constructs a differential drive kinematics object.
      Parameters:
      trackWidthMeters - The track width of the drivetrain. Theoretically, this is the distance between the left wheels and right wheels. However, the empirical value may be larger than the physical measured value due to scrubbing effects.
  • Method Details

    • toChassisSpeeds

      Returns a chassis speed from left and right component velocities using forward kinematics.
      Parameters:
      wheelSpeeds - The left and right velocities.
      Returns:
      The chassis speed.
    • toWheelSpeeds

      Returns left and right component velocities from a chassis speed using inverse kinematics.
      Parameters:
      chassisSpeeds - The linear and angular (dx and dtheta) components that represent the chassis' speed.
      Returns:
      The left and right velocities.
    • toTwist2d

      public Twist2d toTwist2d​(double leftDistanceMeters, double rightDistanceMeters)
      Performs forward kinematics to return the resulting Twist2d from the given left and right side distance 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:
      leftDistanceMeters - The distance measured by the left side encoder.
      rightDistanceMeters - The distance measured by the right side encoder.
      Returns:
      The resulting Twist2d.