WPILibC++ 2023.4.3-108-ge5452e3
|
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 ¢erOfRotation) const |
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity. More... | |
MecanumDriveWheelSpeeds | ToWheelSpeeds (const ChassisSpeeds &chassisSpeeds) const override |
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity. More... | |
ChassisSpeeds | ToChassisSpeeds (const MecanumDriveWheelSpeeds &wheelSpeeds) const override |
Performs forward kinematics to return the resulting chassis state from the given wheel speeds. More... | |
Twist2d | ToTwist2d (const MecanumDriveWheelPositions &wheelDeltas) const override |
Performs forward kinematics to return the resulting Twist2d from the given wheel position deltas. More... | |
virtual ChassisSpeeds | ToChassisSpeeds (const MecanumDriveWheelSpeeds &wheelSpeeds) const=0 |
Performs forward kinematics to return the resulting chassis speed from the wheel speeds. More... | |
virtual MecanumDriveWheelSpeeds | ToWheelSpeeds (const ChassisSpeeds &chassisSpeeds) const=0 |
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity. More... | |
virtual Twist2d | ToTwist2d (const MecanumDriveWheelPositions &wheelDeltas) const=0 |
Performs forward kinematics to return the resulting Twist2d from the given wheel deltas. More... | |
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.
|
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 |
|
overridevirtual |
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.
wheelSpeeds | The current mecanum drive wheel speeds. |
Implements frc::Kinematics< MecanumDriveWheelSpeeds, MecanumDriveWheelPositions >.
|
overridevirtual |
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. |
Implements frc::Kinematics< MecanumDriveWheelSpeeds, MecanumDriveWheelPositions >.
|
inlineoverridevirtual |
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.
chassisSpeeds | The desired chassis speed. |
Implements frc::Kinematics< MecanumDriveWheelSpeeds, MecanumDriveWheelPositions >.
MecanumDriveWheelSpeeds frc::MecanumDriveKinematics::ToWheelSpeeds | ( | const ChassisSpeeds & | chassisSpeeds, |
const Translation2d & | centerOfRotation | ||
) | 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.
chassisSpeeds | The desired chassis speed. |
centerOfRotation | The 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. |