Interface Kinematics<P,S,A>

Type Parameters:
P - The type of the wheel positions.
S - The type of the wheel velocities.
A - The type of the wheel accelerations.
All Superinterfaces:
Interpolator<P>
All Known Implementing Classes:
DifferentialDriveKinematics, MecanumDriveKinematics, SwerveDriveKinematics

public interface Kinematics<P,S,A> extends Interpolator<P>
Helper class that converts a chassis velocity (dx and dtheta components) into wheel velocities and chassis accelerations into wheel accelerations. 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
    copy(P positions)
    Returns a copy of the wheel positions object.
    void
    copyInto(P positions, P output)
    Copies the value of the wheel positions object into the output.
    toChassisAccelerations(A wheelAccelerations)
    Performs forward kinematics to return the resulting chassis accelerations from the wheel accelerations.
    toChassisVelocities(S wheelVelocities)
    Performs forward kinematics to return the resulting chassis velocity from the wheel velocities.
    toTwist2d(P start, P end)
    Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions.
    Performs inverse kinematics to return the wheel accelerations from a desired chassis acceleration.
    Performs inverse kinematics to return the wheel velocities from a desired chassis velocity.

    Methods inherited from interface Interpolator

    interpolate
  • Method Details

    • toChassisVelocities

      Performs forward kinematics to return the resulting chassis velocity from the wheel velocities. This method is often used for odometry -- determining the robot's position on the field using data from the real-world velocity of each wheel on the robot.
      Parameters:
      wheelVelocities - The velocities of the wheels.
      Returns:
      The chassis velocity.
    • toWheelVelocities

      Performs inverse kinematics to return the wheel velocities from a desired chassis velocity. This method is often used to convert joystick values into wheel velocities.
      Parameters:
      chassisVelocities - The desired chassis velocity.
      Returns:
      The wheel velocities.
    • toChassisAccelerations

      Performs forward kinematics to return the resulting chassis accelerations from the wheel accelerations. This method is often used for dynamics calculations -- determining the robot's acceleration on the field using data from the real-world acceleration of each wheel on the robot.
      Parameters:
      wheelAccelerations - The accelerations of the wheels.
      Returns:
      The chassis accelerations.
    • toWheelAccelerations

      Performs inverse kinematics to return the wheel accelerations from a desired chassis acceleration. This method is often used for dynamics calculations -- converting desired robot accelerations into individual wheel accelerations.
      Parameters:
      chassisAccelerations - The desired chassis accelerations.
      Returns:
      The wheel accelerations.
    • toTwist2d

      Twist2d toTwist2d(P start, P end)
      Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions. 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:
      start - The starting distances driven by the wheels.
      end - The ending distances driven by the wheels.
      Returns:
      The resulting Twist2d in the robot's movement.
    • copy

      P copy(P positions)
      Returns a copy of the wheel positions object.
      Parameters:
      positions - The wheel positions object to copy.
      Returns:
      A copy.
    • copyInto

      void copyInto(P positions, P output)
      Copies the value of the wheel positions object into the output.
      Parameters:
      positions - The wheel positions object to copy. Will not be modified.
      output - The output variable of the copy operation. Will have the same value as the positions object after the call.