Package edu.wpi.first.math.kinematics
Interface Kinematics<S,P>
- Type Parameters:
S
- The type of the wheel speeds.P
- The type of the wheel positions.
- All Superinterfaces:
Interpolator<P>
- All Known Implementing Classes:
DifferentialDriveKinematics
,MecanumDriveKinematics
,SwerveDriveKinematics
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 TypeMethodDescriptionReturns a copy of the wheel positions object.void
Copies the value of the wheel positions object into the output.toChassisSpeeds
(S wheelSpeeds) Performs forward kinematics to return the resulting chassis speed from the wheel speeds.Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions.toWheelSpeeds
(ChassisSpeeds chassisSpeeds) Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.Methods inherited from interface edu.wpi.first.math.interpolation.Interpolator
interpolate
-
Method Details
-
toChassisSpeeds
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
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
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
Returns a copy of the wheel positions object.- Parameters:
positions
- The wheel positions object to copy.- Returns:
- A copy.
-
copyInto
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.
-