![]() |
WPILibC++ 2027.0.0-alpha-4
|
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel velocities. More...
#include <wpi/math/kinematics/MecanumDriveKinematics.hpp>
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 ¢erOfRotation) 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 Translation2d & | GetFrontLeft () const |
| Returns the front-left wheel translation. | |
| const Translation2d & | GetFrontRight () const |
| Returns the front-right wheel translation. | |
| const Translation2d & | GetRearLeft () const |
| Returns the rear-left wheel translation. | |
| const Translation2d & | GetRearRight () 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 ¢erOfRotation) 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 |
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.
|
inlineexplicit |
Constructs a mecanum drive kinematics object.
| 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. |
|
default |
|
inline |
Returns the front-left wheel translation.
|
inline |
Returns the front-right wheel translation.
|
inline |
Returns the rear-left wheel translation.
|
inline |
Returns the rear-right wheel translation.
|
inlineoverridevirtual |
Performs interpolation between two values.
| start | The value to start at. |
| end | The value to end at. |
| t | How far between the two values to interpolate. This should be bounded to [0, 1]. |
|
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.
| wheelAccelerations | The accelerations of the wheels. |
|
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.
| wheelVelocities | The current mecanum drive wheel velocities. |
|
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.
| start | The starting distances driven by the wheels. |
| end | The ending distances driven by the wheels. |
| 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.
| wheelDeltas | The change in distance driven by each wheel. |
|
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.
| chassisAccelerations | The desired chassis accelerations. |
| MecanumDriveWheelAccelerations wpi::math::MecanumDriveKinematics::ToWheelAccelerations | ( | const ChassisAccelerations & | chassisAccelerations, |
| const Translation2d & | centerOfRotation ) 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.
| chassisVelocities | The desired chassis velocity. |
| 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.
| 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. |