WPILibC++ 2023.4.3
MecanumDriveKinematics.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <wpi/SymbolExports.h>
8
9#include "Eigen/QR"
10#include "frc/EigenCore.h"
16#include "wpimath/MathShared.h"
17
18namespace frc {
19
20/**
21 * Helper class that converts a chassis velocity (dx, dy, and dtheta components)
22 * into individual wheel speeds.
23 *
24 * The inverse kinematics (converting from a desired chassis velocity to
25 * individual wheel speeds) uses the relative locations of the wheels with
26 * respect to the center of rotation. The center of rotation for inverse
27 * kinematics is also variable. This means that you can set your set your center
28 * of rotation in a corner of the robot to perform special evasion maneuvers.
29 *
30 * Forward kinematics (converting an array of wheel speeds into the overall
31 * chassis motion) is performs the exact opposite of what inverse kinematics
32 * does. Since this is an overdetermined system (more equations than variables),
33 * we use a least-squares approximation.
34 *
35 * The inverse kinematics: [wheelSpeeds] = [wheelLocations] * [chassisSpeeds]
36 * We take the Moore-Penrose pseudoinverse of [wheelLocations] and then
37 * multiply by [wheelSpeeds] to get our chassis speeds.
38 *
39 * Forward kinematics is also used for odometry -- determining the position of
40 * the robot on the field using encoders and a gyro.
41 */
43 public:
44 /**
45 * Constructs a mecanum drive kinematics object.
46 *
47 * @param frontLeftWheel The location of the front-left wheel relative to the
48 * physical center of the robot.
49 * @param frontRightWheel The location of the front-right wheel relative to
50 * the physical center of the robot.
51 * @param rearLeftWheel The location of the rear-left wheel relative to the
52 * physical center of the robot.
53 * @param rearRightWheel The location of the rear-right wheel relative to the
54 * physical center of the robot.
55 */
56 explicit MecanumDriveKinematics(Translation2d frontLeftWheel,
57 Translation2d frontRightWheel,
58 Translation2d rearLeftWheel,
59 Translation2d rearRightWheel)
60 : m_frontLeftWheel{frontLeftWheel},
61 m_frontRightWheel{frontRightWheel},
62 m_rearLeftWheel{rearLeftWheel},
63 m_rearRightWheel{rearRightWheel} {
64 SetInverseKinematics(frontLeftWheel, frontRightWheel, rearLeftWheel,
65 rearRightWheel);
66 m_forwardKinematics = m_inverseKinematics.householderQr();
69 }
70
72
73 /**
74 * Performs inverse kinematics to return the wheel speeds from a desired
75 * chassis velocity. This method is often used to convert joystick values into
76 * wheel speeds.
77 *
78 * This function also supports variable centers of rotation. During normal
79 * operations, the center of rotation is usually the same as the physical
80 * center of the robot; therefore, the argument is defaulted to that use case.
81 * However, if you wish to change the center of rotation for evasive
82 * maneuvers, vision alignment, or for any other use case, you can do so.
83 *
84 * @param chassisSpeeds The desired chassis speed.
85 * @param centerOfRotation The center of rotation. For example, if you set the
86 * center of rotation at one corner of the robot and
87 * provide a chassis speed that only has a dtheta
88 * component, the robot will rotate around that
89 * corner.
90 *
91 * @return The wheel speeds. Use caution because they are not normalized.
92 * Sometimes, a user input may cause one of the wheel speeds to go
93 * above the attainable max velocity. Use the
94 * MecanumDriveWheelSpeeds::Normalize() function to rectify this
95 * issue. In addition, you can leverage the power of C++17 to directly
96 * assign the wheel speeds to variables:
97 *
98 * @code{.cpp}
99 * auto [fl, fr, bl, br] = kinematics.ToWheelSpeeds(chassisSpeeds);
100 * @endcode
101 */
103 const ChassisSpeeds& chassisSpeeds,
104 const Translation2d& centerOfRotation = Translation2d{}) const;
105
106 /**
107 * Performs forward kinematics to return the resulting chassis state from the
108 * given wheel speeds. This method is often used for odometry -- determining
109 * the robot's position on the field using data from the real-world speed of
110 * each wheel on the robot.
111 *
112 * @param wheelSpeeds The current mecanum drive wheel speeds.
113 *
114 * @return The resulting chassis speed.
115 */
117 const MecanumDriveWheelSpeeds& wheelSpeeds) const;
118
119 /**
120 * Performs forward kinematics to return the resulting Twist2d from the
121 * given wheel position deltas. This method is often used for odometry --
122 * determining the robot's position on the field using data from the
123 * distance driven by each wheel on the robot.
124 *
125 * @param wheelDeltas The change in distance driven by each wheel.
126 *
127 * @return The resulting chassis speed.
128 */
130
131 private:
132 mutable Matrixd<4, 3> m_inverseKinematics;
133 Eigen::HouseholderQR<Matrixd<4, 3>> m_forwardKinematics;
134 Translation2d m_frontLeftWheel;
135 Translation2d m_frontRightWheel;
136 Translation2d m_rearLeftWheel;
137 Translation2d m_rearRightWheel;
138
139 mutable Translation2d m_previousCoR;
140
141 /**
142 * Construct inverse kinematics matrix from wheel locations.
143 *
144 * @param fl The location of the front-left wheel relative to the physical
145 * center of the robot.
146 * @param fr The location of the front-right wheel relative to the physical
147 * center of the robot.
148 * @param rl The location of the rear-left wheel relative to the physical
149 * center of the robot.
150 * @param rr The location of the rear-right wheel relative to the physical
151 * center of the robot.
152 */
153 void SetInverseKinematics(Translation2d fl, Translation2d fr,
154 Translation2d rl, Translation2d rr) const;
155};
156
157} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Householder QR decomposition of a matrix.
Definition: HouseholderQR.h:58
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:180
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition: MecanumDriveKinematics.h:42
Twist2d ToTwist2d(const MecanumDriveWheelPositions &wheelDeltas) const
Performs forward kinematics to return the resulting Twist2d from the given wheel position deltas.
MecanumDriveWheelSpeeds ToWheelSpeeds(const ChassisSpeeds &chassisSpeeds, const Translation2d &centerOfRotation=Translation2d{}) const
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.
MecanumDriveKinematics(const MecanumDriveKinematics &)=default
MecanumDriveKinematics(Translation2d frontLeftWheel, Translation2d frontRightWheel, Translation2d rearLeftWheel, Translation2d rearRightWheel)
Constructs a mecanum drive kinematics object.
Definition: MecanumDriveKinematics.h:56
ChassisSpeeds ToChassisSpeeds(const MecanumDriveWheelSpeeds &wheelSpeeds) const
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:73
Definition: AprilTagFieldLayout.h:22
Represents the speed of a robot chassis.
Definition: ChassisSpeeds.h:25
Represents the wheel speeds for a mecanum drive drivetrain.
Definition: MecanumDriveWheelPositions.h:15
Represents the wheel speeds for a mecanum drive drivetrain.
Definition: MecanumDriveWheelSpeeds.h:15
A change in distance along a 2D arc since the last pose update.
Definition: Twist2d.h:21