Robot Core Documentation
|
Public Member Functions | |
ChassisSpeeds | toChassisSpeeds (S wheelSpeeds) |
S | toWheelSpeeds (ChassisSpeeds chassisSpeeds) |
Twist2d | toTwist2d (P start, P end) |
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
).
<S> | The type of the wheel speeds. |
<P> | The type of the wheel positions. |
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.
wheelSpeeds | The speeds of the wheels. |
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.
start | The starting distances driven by the wheels. |
end | The ending distances driven by the wheels. |
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.
chassisSpeeds | The desired chassis speed. |