Interface Kinematics<S,​P>

Type Parameters:
S - The type of the wheel speeds.
P - The type of the wheel positions.
All Known Implementing Classes:
DifferentialDriveKinematics, MecanumDriveKinematics, SwerveDriveKinematics

public interface Kinematics<S,​P>
Helper class that converts a chassis velocity (dx and dtheta components) into wheel speeds. Robot code should not use this directly- Instead, use the particular type for your drivetrain (e.g., DifferentialDriveKinematics).
  • Method Summary

    Modifier and Type Method Description
    ChassisSpeeds toChassisSpeeds​(S wheelSpeeds)
    Performs forward kinematics to return the resulting chassis speed from the wheel speeds.
    Twist2d toTwist2d​(P wheelDeltas)
    Performs forward kinematics to return the resulting from the given wheel deltas.
    S toWheelSpeeds​(ChassisSpeeds chassisSpeeds)
    Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.
  • Method Details

    • toChassisSpeeds

      ChassisSpeeds toChassisSpeeds​(S wheelSpeeds)
      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.
      Parameters:
      wheelSpeeds - The speeds of the wheels.
      Returns:
      The chassis speed.
    • toWheelSpeeds

      S toWheelSpeeds​(ChassisSpeeds chassisSpeeds)
      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.
      Parameters:
      chassisSpeeds - The desired chassis speed.
      Returns:
      The wheel speeds.
    • toTwist2d

      Twist2d toTwist2d​(P wheelDeltas)
      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.
      Parameters:
      wheelDeltas - The distances driven by each wheel.
      Returns:
      The resulting Twist2d in the robot's movement.