MecanumDriveKinematics
- class wpimath.MecanumDriveKinematics(frontLeftWheel: wpimath._wpimath.Translation2d, frontRightWheel: wpimath._wpimath.Translation2d, rearLeftWheel: wpimath._wpimath.Translation2d, rearRightWheel: wpimath._wpimath.Translation2d)
Bases:
MecanumDriveKinematicsBaseHelper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel velocities.
The inverse kinematics (converting from a desired chassis velocity to individual wheel velocities) 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 set your center of rotation in a corner of the robot to perform special evasion maneuvers.
Forward kinematics (converting an array of wheel velocities 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: [wheelVelocities] = [wheelLocations] * [chassisVelocities] We take the Moore-Penrose pseudoinverse of [wheelLocations] and then multiply by [wheelVelocities] to get our chassis velocities.
Forward kinematics is also used for odometry – determining the position of the robot on the field using encoders and a gyro.
Constructs a mecanum drive kinematics object.
- Parameters:
frontLeftWheel – The location of the front-left wheel relative to the physical center of the robot.
frontRightWheel – The location of the front-right wheel relative to the physical center of the robot.
rearLeftWheel – The location of the rear-left wheel relative to the physical center of the robot.
rearRightWheel – The location of the rear-right wheel relative to the physical center of the robot.
- WPIStruct = <capsule object "WPyStruct">
- getFrontLeft() wpimath._wpimath.Translation2d
Returns the front-left wheel translation.
- Returns:
The front-left wheel translation.
- getFrontRight() wpimath._wpimath.Translation2d
Returns the front-right wheel translation.
- Returns:
The front-right wheel translation.
- getRearLeft() wpimath._wpimath.Translation2d
Returns the rear-left wheel translation.
- Returns:
The rear-left wheel translation.
- getRearRight() wpimath._wpimath.Translation2d
Returns the rear-right wheel translation.
- Returns:
The rear-right wheel translation.
- interpolate(start: wpimath._wpimath.MecanumDriveWheelPositions, end: wpimath._wpimath.MecanumDriveWheelPositions, t: SupportsFloat | SupportsIndex) wpimath._wpimath.MecanumDriveWheelPositions
- toChassisAccelerations(wheelAccelerations: wpimath._wpimath.MecanumDriveWheelAccelerations) wpimath._wpimath.ChassisAccelerations
- toChassisVelocities(wheelVelocities: wpimath._wpimath.MecanumDriveWheelVelocities) wpimath._wpimath.ChassisVelocities
Performs forward kinematics to return the resulting chassis state from the given 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 current mecanum drive wheel velocities.
- Returns:
The resulting chassis velocity.
- toTwist2d(*args, **kwargs)
Overloaded function.
toTwist2d(self: wpimath._wpimath.MecanumDriveKinematics, start: wpimath._wpimath.MecanumDriveWheelPositions, end: wpimath._wpimath.MecanumDriveWheelPositions) -> wpimath._wpimath.Twist2d
toTwist2d(self: wpimath._wpimath.MecanumDriveKinematics, wheelDeltas: wpimath._wpimath.MecanumDriveWheelPositions) -> wpimath._wpimath.Twist2d
Performs forward kinematics to return the resulting Twist2d from the given wheel position deltas. This method is often used for odometry – determining the robot’s position on the field using data from the distance driven by each wheel on the robot.
- Parameters:
wheelDeltas – The change in distance driven by each wheel.
- Returns:
The resulting chassis velocity.
- toWheelAccelerations(*args, **kwargs)
Overloaded function.
toWheelAccelerations(self: wpimath._wpimath.MecanumDriveKinematics, chassisAccelerations: wpimath._wpimath.ChassisAccelerations, centerOfRotation: wpimath._wpimath.Translation2d) -> wpimath._wpimath.MecanumDriveWheelAccelerations
toWheelAccelerations(self: wpimath._wpimath.MecanumDriveKinematics, chassisAccelerations: wpimath._wpimath.ChassisAccelerations) -> wpimath._wpimath.MecanumDriveWheelAccelerations
- toWheelVelocities(*args, **kwargs)
Overloaded function.
toWheelVelocities(self: wpimath._wpimath.MecanumDriveKinematics, chassisVelocities: wpimath._wpimath.ChassisVelocities, centerOfRotation: wpimath._wpimath.Translation2d) -> wpimath._wpimath.MecanumDriveWheelVelocities
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.
This function also supports variable centers of rotation. During normal operations, the center of rotation is usually the same as the physical center of the robot; therefore, the argument is defaulted to that use case. However, if you wish to change the center of rotation for evasive maneuvers, vision alignment, or for any other use case, you can do so.
- Parameters:
chassisVelocities – The desired chassis velocity.
centerOfRotation – The center of rotation. For example, if you set the center of rotation at one corner of the robot and provide a chassis velocity that only has a dtheta component, the robot will rotate around that corner.
- Returns:
The wheel velocities. Use caution because they are not normalized. Sometimes, a user input may cause one of the wheel velocities to go above the attainable max velocity. Use the
MecanumDriveWheelVelocities.normalize()method to rectify this issue. In addition, you can use Python unpacking syntax to directly assign the wheel velocities to variables:fl, fr, bl, br = kinematics.toWheelVelocities(chassisVelocities)
toWheelVelocities(self: wpimath._wpimath.MecanumDriveKinematics, chassisVelocities: wpimath._wpimath.ChassisVelocities) -> wpimath._wpimath.MecanumDriveWheelVelocities
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.
This function also supports variable centers of rotation. During normal operations, the center of rotation is usually the same as the physical center of the robot; therefore, the argument is defaulted to that use case. However, if you wish to change the center of rotation for evasive maneuvers, vision alignment, or for any other use case, you can do so.
- Parameters:
chassisVelocities – The desired chassis velocity.
centerOfRotation – The center of rotation. For example, if you set the center of rotation at one corner of the robot and provide a chassis velocity that only has a dtheta component, the robot will rotate around that corner.
- Returns:
The wheel velocities. Use caution because they are not normalized. Sometimes, a user input may cause one of the wheel velocities to go above the attainable max velocity. Use the
MecanumDriveWheelVelocities.normalize()method to rectify this issue. In addition, you can use Python unpacking syntax to directly assign the wheel velocities to variables:fl, fr, bl, br = kinematics.toWheelVelocities(chassisVelocities)