Class MecanumDriveKinematics

java.lang.Object
edu.wpi.first.math.kinematics.MecanumDriveKinematics
All Implemented Interfaces:
Kinematics<MecanumDriveWheelSpeeds,​MecanumDriveWheelPositions>, ProtobufSerializable, StructSerializable, WPISerializable

public class MecanumDriveKinematics
extends Object
implements Kinematics<MecanumDriveWheelSpeeds,​MecanumDriveWheelPositions>, ProtobufSerializable, StructSerializable
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel speeds.

The inverse kinematics (converting from a desired chassis velocity to individual wheel speeds) uses the relative locations of the wheels with respect to the center of rotation. The center of rotation for inverse kinematics is also variable. This means that you can set your center of rotation in a corner of the robot to perform special evasion maneuvers.

Forward kinematics (converting an array of wheel speeds into the overall chassis motion) is performs the exact opposite of what inverse kinematics does. Since this is an overdetermined system (more equations than variables), we use a least-squares approximation.

The inverse kinematics: [wheelSpeeds] = [wheelLocations] * [chassisSpeeds] We take the Moore-Penrose pseudoinverse of [wheelLocations] and then multiply by [wheelSpeeds] to get our chassis speeds.

Forward kinematics is also used for odometry -- determining the position of the robot on the field using encoders and a gyro.