public class MecanumOdoKinematics
extends java.lang.Object
Constructor and Description |
---|
MecanumOdoKinematics(Translation2d frontLeftWheelMeters,
Translation2d frontRightWheelMeters,
Translation2d rearLeftWheelMeters,
Translation2d rearRightWheelMeters,
double auxDistance,
double wheelbaseWidth)
Constructs a mecanum drive kinematics object.
|
Modifier and Type | Method and Description |
---|---|
ChassisSpeeds |
toChassisSpeeds(OdoWheelSpeeds wheelSpeeds)
Performs forward kinematics to return the resulting chassis state from the given wheel speeds.
|
MecanumDriveWheelSpeeds |
toWheelSpeeds(ChassisSpeeds chassisSpeeds)
Performs inverse kinematics.
|
MecanumDriveWheelSpeeds |
toWheelSpeeds(ChassisSpeeds chassisSpeeds,
Translation2d centerOfRotationMeters)
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.
|
public MecanumOdoKinematics(Translation2d frontLeftWheelMeters, Translation2d frontRightWheelMeters, Translation2d rearLeftWheelMeters, Translation2d rearRightWheelMeters, double auxDistance, double wheelbaseWidth)
frontLeftWheelMeters
- The location of the front-left wheel relative to the
physical center of the robot.frontRightWheelMeters
- The location of the front-right wheel relative to
the physical center of the robot.rearLeftWheelMeters
- The location of the rear-left wheel relative to the
physical center of the robot.rearRightWheelMeters
- The location of the rear-right wheel relative to the
physical center of the robot.public MecanumDriveWheelSpeeds toWheelSpeeds(ChassisSpeeds chassisSpeeds, Translation2d centerOfRotationMeters)
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 manuevers, vision alignment, or for any other use case, you can do so.
chassisSpeeds
- The desired chassis speed.centerOfRotationMeters
- 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.MecanumDriveWheelSpeeds.normalize(double)
function to rectify this issue.public MecanumDriveWheelSpeeds toWheelSpeeds(ChassisSpeeds chassisSpeeds)
toWheelSpeeds(ChassisSpeeds, Translation2d)
for more
information.chassisSpeeds
- The desired chassis speed.public ChassisSpeeds toChassisSpeeds(OdoWheelSpeeds wheelSpeeds)
wheelSpeeds
- The current mecanum drive wheel speeds.