WPILibC++ 2023.4.3
frc::MecanumDriveKinematics Class Reference

Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel speeds. More...

#include <frc/kinematics/MecanumDriveKinematics.h>

Public Member Functions

 MecanumDriveKinematics (Translation2d frontLeftWheel, Translation2d frontRightWheel, Translation2d rearLeftWheel, Translation2d rearRightWheel)
 Constructs a mecanum drive kinematics object. More...
 
 MecanumDriveKinematics (const MecanumDriveKinematics &)=default
 
MecanumDriveWheelSpeeds ToWheelSpeeds (const ChassisSpeeds &chassisSpeeds, const Translation2d &centerOfRotation=Translation2d{}) const
 Performs inverse kinematics to return the wheel speeds from a desired chassis velocity. More...
 
ChassisSpeeds ToChassisSpeeds (const MecanumDriveWheelSpeeds &wheelSpeeds) const
 Performs forward kinematics to return the resulting chassis state from the given wheel speeds. More...
 
Twist2d ToTwist2d (const MecanumDriveWheelPositions &wheelDeltas) const
 Performs forward kinematics to return the resulting Twist2d from the given wheel position deltas. More...
 

Detailed Description

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

Constructor & Destructor Documentation

◆ MecanumDriveKinematics() [1/2]

frc::MecanumDriveKinematics::MecanumDriveKinematics ( Translation2d  frontLeftWheel,
Translation2d  frontRightWheel,
Translation2d  rearLeftWheel,
Translation2d  rearRightWheel 
)
inlineexplicit

Constructs a mecanum drive kinematics object.

Parameters
frontLeftWheelThe location of the front-left wheel relative to the physical center of the robot.
frontRightWheelThe location of the front-right wheel relative to the physical center of the robot.
rearLeftWheelThe location of the rear-left wheel relative to the physical center of the robot.
rearRightWheelThe location of the rear-right wheel relative to the physical center of the robot.

◆ MecanumDriveKinematics() [2/2]

frc::MecanumDriveKinematics::MecanumDriveKinematics ( const MecanumDriveKinematics )
default

Member Function Documentation

◆ ToChassisSpeeds()

ChassisSpeeds frc::MecanumDriveKinematics::ToChassisSpeeds ( const MecanumDriveWheelSpeeds wheelSpeeds) const

Performs forward kinematics to return the resulting chassis state from the given 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 current mecanum drive wheel speeds.
Returns
The resulting chassis speed.

◆ ToTwist2d()

Twist2d frc::MecanumDriveKinematics::ToTwist2d ( const MecanumDriveWheelPositions wheelDeltas) const

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
wheelDeltasThe change in distance driven by each wheel.
Returns
The resulting chassis speed.

◆ ToWheelSpeeds()

MecanumDriveWheelSpeeds frc::MecanumDriveKinematics::ToWheelSpeeds ( const ChassisSpeeds chassisSpeeds,
const Translation2d centerOfRotation = Translation2d{} 
) const

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.

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
chassisSpeedsThe desired chassis speed.
centerOfRotationThe center of rotation. For example, if you set the center of rotation at one corner of the robot and provide a chassis speed that only has a dtheta component, the robot will rotate around that corner.
Returns
The wheel speeds. Use caution because they are not normalized. Sometimes, a user input may cause one of the wheel speeds to go above the attainable max velocity. Use the MecanumDriveWheelSpeeds::Normalize() function to rectify this issue. In addition, you can leverage the power of C++17 to directly assign the wheel speeds to variables:
auto [fl, fr, bl, br] = kinematics.ToWheelSpeeds(chassisSpeeds);

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