WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
wpi::math::MecanumDriveKinematics Class Reference

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

#include <wpi/math/kinematics/MecanumDriveKinematics.hpp>

Inheritance diagram for wpi::math::MecanumDriveKinematics:
wpi::math::Kinematics< MecanumDriveWheelPositions, MecanumDriveWheelVelocities, MecanumDriveWheelAccelerations >

Public Member Functions

 MecanumDriveKinematics (Translation2d frontLeftWheel, Translation2d frontRightWheel, Translation2d rearLeftWheel, Translation2d rearRightWheel)
 Constructs a mecanum drive kinematics object.
 MecanumDriveKinematics (const MecanumDriveKinematics &)=default
MecanumDriveWheelVelocities ToWheelVelocities (const ChassisVelocities &chassisVelocities, const Translation2d &centerOfRotation) const
 Performs inverse kinematics to return the wheel velocities from a desired chassis velocity.
MecanumDriveWheelVelocities ToWheelVelocities (const ChassisVelocities &chassisVelocities) const override
 Performs inverse kinematics to return the wheel velocities from a desired chassis velocity.
ChassisVelocities ToChassisVelocities (const MecanumDriveWheelVelocities &wheelVelocities) const override
 Performs forward kinematics to return the resulting chassis state from the given wheel velocities.
Twist2d ToTwist2d (const MecanumDriveWheelPositions &start, const MecanumDriveWheelPositions &end) const override
 Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions.
Twist2d ToTwist2d (const MecanumDriveWheelPositions &wheelDeltas) const
 Performs forward kinematics to return the resulting Twist2d from the given wheel position deltas.
const Translation2dGetFrontLeft () const
 Returns the front-left wheel translation.
const Translation2dGetFrontRight () const
 Returns the front-right wheel translation.
const Translation2dGetRearLeft () const
 Returns the rear-left wheel translation.
const Translation2dGetRearRight () const
 Returns the rear-right wheel translation.
MecanumDriveWheelPositions Interpolate (const MecanumDriveWheelPositions &start, const MecanumDriveWheelPositions &end, double t) const override
 Performs interpolation between two values.
ChassisAccelerations ToChassisAccelerations (const MecanumDriveWheelAccelerations &wheelAccelerations) const override
 Performs forward kinematics to return the resulting chassis accelerations from the wheel accelerations.
MecanumDriveWheelAccelerations ToWheelAccelerations (const ChassisAccelerations &chassisAccelerations, const Translation2d &centerOfRotation) const
MecanumDriveWheelAccelerations ToWheelAccelerations (const ChassisAccelerations &chassisAccelerations) const override
 Performs inverse kinematics to return the wheel accelerations from a desired chassis acceleration.
Public Member Functions inherited from wpi::math::Kinematics< MecanumDriveWheelPositions, MecanumDriveWheelVelocities, MecanumDriveWheelAccelerations >
virtual ~Kinematics () noexcept=default

Detailed Description

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

Constructor & Destructor Documentation

◆ MecanumDriveKinematics() [1/2]

wpi::math::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]

wpi::math::MecanumDriveKinematics::MecanumDriveKinematics ( const MecanumDriveKinematics & )
default

Member Function Documentation

◆ GetFrontLeft()

const Translation2d & wpi::math::MecanumDriveKinematics::GetFrontLeft ( ) const
inline

Returns the front-left wheel translation.

Returns
The front-left wheel translation.

◆ GetFrontRight()

const Translation2d & wpi::math::MecanumDriveKinematics::GetFrontRight ( ) const
inline

Returns the front-right wheel translation.

Returns
The front-right wheel translation.

◆ GetRearLeft()

const Translation2d & wpi::math::MecanumDriveKinematics::GetRearLeft ( ) const
inline

Returns the rear-left wheel translation.

Returns
The rear-left wheel translation.

◆ GetRearRight()

const Translation2d & wpi::math::MecanumDriveKinematics::GetRearRight ( ) const
inline

Returns the rear-right wheel translation.

Returns
The rear-right wheel translation.

◆ Interpolate()

MecanumDriveWheelPositions wpi::math::MecanumDriveKinematics::Interpolate ( const MecanumDriveWheelPositions & start,
const MecanumDriveWheelPositions & end,
double t ) const
inlineoverridevirtual

Performs interpolation between two values.

Parameters
startThe value to start at.
endThe value to end at.
tHow far between the two values to interpolate. This should be bounded to [0, 1].
Returns
The interpolated value.

Implements wpi::math::Kinematics< MecanumDriveWheelPositions, MecanumDriveWheelVelocities, MecanumDriveWheelAccelerations >.

◆ ToChassisAccelerations()

ChassisAccelerations wpi::math::MecanumDriveKinematics::ToChassisAccelerations ( const MecanumDriveWheelAccelerations & wheelAccelerations) const
overridevirtual

Performs forward kinematics to return the resulting chassis accelerations from the wheel accelerations.

This method is often used for dynamics calculations – determining the robot's acceleration on the field using data from the real-world acceleration of each wheel on the robot.

Parameters
wheelAccelerationsThe accelerations of the wheels.
Returns
The chassis accelerations.

Implements wpi::math::Kinematics< MecanumDriveWheelPositions, MecanumDriveWheelVelocities, MecanumDriveWheelAccelerations >.

◆ ToChassisVelocities()

ChassisVelocities wpi::math::MecanumDriveKinematics::ToChassisVelocities ( const MecanumDriveWheelVelocities & wheelVelocities) const
overridevirtual

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
wheelVelocitiesThe current mecanum drive wheel velocities.
Returns
The resulting chassis velocity.

Implements wpi::math::Kinematics< MecanumDriveWheelPositions, MecanumDriveWheelVelocities, MecanumDriveWheelAccelerations >.

◆ ToTwist2d() [1/2]

Twist2d wpi::math::MecanumDriveKinematics::ToTwist2d ( const MecanumDriveWheelPositions & start,
const MecanumDriveWheelPositions & end ) const
overridevirtual

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.

Implements wpi::math::Kinematics< MecanumDriveWheelPositions, MecanumDriveWheelVelocities, MecanumDriveWheelAccelerations >.

◆ ToTwist2d() [2/2]

Twist2d wpi::math::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 velocity.

◆ ToWheelAccelerations() [1/2]

MecanumDriveWheelAccelerations wpi::math::MecanumDriveKinematics::ToWheelAccelerations ( const ChassisAccelerations & chassisAccelerations) const
inlineoverridevirtual

Performs inverse kinematics to return the wheel accelerations from a desired chassis acceleration.

This method is often used for dynamics calculations – converting desired robot accelerations into individual wheel accelerations.

Parameters
chassisAccelerationsThe desired chassis accelerations.
Returns
The wheel accelerations.

Implements wpi::math::Kinematics< MecanumDriveWheelPositions, MecanumDriveWheelVelocities, MecanumDriveWheelAccelerations >.

◆ ToWheelAccelerations() [2/2]

MecanumDriveWheelAccelerations wpi::math::MecanumDriveKinematics::ToWheelAccelerations ( const ChassisAccelerations & chassisAccelerations,
const Translation2d & centerOfRotation ) const

◆ ToWheelVelocities() [1/2]

MecanumDriveWheelVelocities wpi::math::MecanumDriveKinematics::ToWheelVelocities ( const ChassisVelocities & chassisVelocities) const
inlineoverridevirtual

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.

Parameters
chassisVelocitiesThe desired chassis velocity.
Returns
The wheel velocities.

Implements wpi::math::Kinematics< MecanumDriveWheelPositions, MecanumDriveWheelVelocities, MecanumDriveWheelAccelerations >.

◆ ToWheelVelocities() [2/2]

MecanumDriveWheelVelocities wpi::math::MecanumDriveKinematics::ToWheelVelocities ( const ChassisVelocities & chassisVelocities,
const Translation2d & centerOfRotation ) const

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
chassisVelocitiesThe desired chassis velocity.
centerOfRotationThe 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() function to rectify this issue. In addition, you can leverage the power of C++17 to directly assign the wheel velocities to variables:
auto [fl, fr, bl, br] = kinematics.ToWheelVelocities(chassisVelocities);

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