44 :
public Kinematics<MecanumDriveWheelSpeeds, MecanumDriveWheelPositions> {
62 : m_frontLeftWheel{frontLeftWheel},
63 m_frontRightWheel{frontRightWheel},
64 m_rearLeftWheel{rearLeftWheel},
65 m_rearRightWheel{rearRightWheel} {
66 SetInverseKinematics(frontLeftWheel, frontRightWheel, rearLeftWheel,
68 m_forwardKinematics = m_inverseKinematics.householderQr();
110 return ToWheelSpeeds(chassisSpeeds, {});
172 return start.Interpolate(end, t);
177 Eigen::HouseholderQR<Matrixd<4, 3>> m_forwardKinematics;
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition Kinematics.h:25
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition MecanumDriveKinematics.h:44
MecanumDriveWheelSpeeds ToWheelSpeeds(const ChassisSpeeds &chassisSpeeds, const Translation2d ¢erOfRotation) const
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.
Twist2d ToTwist2d(const MecanumDriveWheelPositions &wheelDeltas) const
Performs forward kinematics to return the resulting Twist2d from the given wheel position deltas.
const Translation2d & GetRearRight() const
Returns the rear-right wheel translation.
Definition MecanumDriveKinematics.h:167
const Translation2d & GetFrontRight() const
Returns the front-right wheel translation.
Definition MecanumDriveKinematics.h:153
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.
MecanumDriveKinematics(const MecanumDriveKinematics &)=default
MecanumDriveKinematics(Translation2d frontLeftWheel, Translation2d frontRightWheel, Translation2d rearLeftWheel, Translation2d rearRightWheel)
Constructs a mecanum drive kinematics object.
Definition MecanumDriveKinematics.h:58
const Translation2d & GetFrontLeft() const
Returns the front-left wheel translation.
Definition MecanumDriveKinematics.h:146
const Translation2d & GetRearLeft() const
Returns the rear-left wheel translation.
Definition MecanumDriveKinematics.h:160
MecanumDriveWheelSpeeds ToWheelSpeeds(const ChassisSpeeds &chassisSpeeds) const override
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.
Definition MecanumDriveKinematics.h:108
MecanumDriveWheelPositions Interpolate(const MecanumDriveWheelPositions &start, const MecanumDriveWheelPositions &end, double t) const override
Performs interpolation between two values.
Definition MecanumDriveKinematics.h:169
ChassisSpeeds ToChassisSpeeds(const MecanumDriveWheelSpeeds &wheelSpeeds) const override
Performs forward kinematics to return the resulting chassis state from the given wheel speeds.
Represents a translation in 2D space.
Definition Translation2d.h:29
static void ReportUsage(MathUsageId id, int count)
Definition MathShared.h:75
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
@ kKinematics_MecanumDrive
Represents the speed of a robot chassis.
Definition ChassisSpeeds.h:25
Represents the wheel positions for a mecanum drive drivetrain.
Definition MecanumDriveWheelPositions.h:16
Represents the wheel speeds for a mecanum drive drivetrain.
Definition MecanumDriveWheelSpeeds.h:20
A change in distance along a 2D arc since the last pose update.
Definition Twist2d.h:22