Robot Core Documentation
Loading...
Searching...
No Matches
edu.wpi.first.math.kinematics.Kinematics< S, P > Interface Template Reference

Public Member Functions

ChassisSpeeds toChassisSpeeds (S wheelSpeeds)
 
toWheelSpeeds (ChassisSpeeds chassisSpeeds)
 
Twist2d toTwist2d (P start, P end)
 

Detailed Description

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).

Parameters
<S>The type of the wheel speeds.
<P>The type of the wheel positions.

Member Function Documentation

◆ toChassisSpeeds()

ChassisSpeeds edu.wpi.first.math.kinematics.Kinematics< S, P >.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
wheelSpeedsThe speeds of the wheels.
Returns
The chassis speed.

◆ toTwist2d()

Twist2d edu.wpi.first.math.kinematics.Kinematics< S, P >.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
startThe starting distances driven by the wheels.
endThe ending distances driven by the wheels.
Returns
The resulting Twist2d in the robot's movement.

◆ toWheelSpeeds()

S edu.wpi.first.math.kinematics.Kinematics< S, P >.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
chassisSpeedsThe desired chassis speed.
Returns
The wheel speeds.

The documentation for this interface was generated from the following file: