WPILibC++ 2023.4.3
SwerveDriveKinematics.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 <cstddef>
8
9#include <wpi/SymbolExports.h>
10#include <wpi/array.h>
11
12#include "Eigen/QR"
13#include "frc/EigenCore.h"
20#include "units/velocity.h"
21#include "wpimath/MathShared.h"
22
23namespace frc {
24/**
25 * Helper class that converts a chassis velocity (dx, dy, and dtheta components)
26 * into individual module states (speed and angle).
27 *
28 * The inverse kinematics (converting from a desired chassis velocity to
29 * individual module states) uses the relative locations of the modules with
30 * respect to the center of rotation. The center of rotation for inverse
31 * kinematics is also variable. This means that you can set your set your center
32 * of rotation in a corner of the robot to perform special evasion maneuvers.
33 *
34 * Forward kinematics (converting an array of module states into the overall
35 * chassis motion) is performs the exact opposite of what inverse kinematics
36 * does. Since this is an overdetermined system (more equations than variables),
37 * we use a least-squares approximation.
38 *
39 * The inverse kinematics: [moduleStates] = [moduleLocations] * [chassisSpeeds]
40 * We take the Moore-Penrose pseudoinverse of [moduleLocations] and then
41 * multiply by [moduleStates] to get our chassis speeds.
42 *
43 * Forward kinematics is also used for odometry -- determining the position of
44 * the robot on the field using encoders and a gyro.
45 */
46template <size_t NumModules>
48 public:
49 /**
50 * Constructs a swerve drive kinematics object. This takes in a variable
51 * number of wheel locations as Translation2ds. The order in which you pass in
52 * the wheel locations is the same order that you will receive the module
53 * states when performing inverse kinematics. It is also expected that you
54 * pass in the module states in the same order when calling the forward
55 * kinematics methods.
56 *
57 * @param wheel The location of the first wheel relative to the physical
58 * center of the robot.
59 * @param wheels The locations of the other wheels relative to the physical
60 * center of the robot.
61 */
62 template <typename... Wheels>
63 explicit SwerveDriveKinematics(Translation2d wheel, Wheels&&... wheels)
64 : m_modules{wheel, wheels...}, m_moduleStates(wpi::empty_array) {
65 static_assert(sizeof...(wheels) >= 1,
66 "A swerve drive requires at least two modules");
67
68 for (size_t i = 0; i < NumModules; i++) {
69 // clang-format off
70 m_inverseKinematics.template block<2, 3>(i * 2, 0) <<
71 1, 0, (-m_modules[i].Y()).value(),
72 0, 1, (+m_modules[i].X()).value();
73 // clang-format on
74 }
75
76 m_forwardKinematics = m_inverseKinematics.householderQr();
77
80 }
81
84 : m_modules{wheels}, m_moduleStates(wpi::empty_array) {
85 for (size_t i = 0; i < NumModules; i++) {
86 // clang-format off
87 m_inverseKinematics.template block<2, 3>(i * 2, 0) <<
88 1, 0, (-m_modules[i].Y()).value(),
89 0, 1, (+m_modules[i].X()).value();
90 // clang-format on
91 }
92
93 m_forwardKinematics = m_inverseKinematics.householderQr();
94
97 }
98
100
101 /**
102 * Performs inverse kinematics to return the module states from a desired
103 * chassis velocity. This method is often used to convert joystick values into
104 * module speeds and angles.
105 *
106 * This function also supports variable centers of rotation. During normal
107 * operations, the center of rotation is usually the same as the physical
108 * center of the robot; therefore, the argument is defaulted to that use case.
109 * However, if you wish to change the center of rotation for evasive
110 * maneuvers, vision alignment, or for any other use case, you can do so.
111 *
112 * In the case that the desired chassis speeds are zero (i.e. the robot will
113 * be stationary), the previously calculated module angle will be maintained.
114 *
115 * @param chassisSpeeds The desired chassis speed.
116 * @param centerOfRotation The center of rotation. For example, if you set the
117 * center of rotation at one corner of the robot and provide a chassis speed
118 * that only has a dtheta component, the robot will rotate around that corner.
119 *
120 * @return An array containing the module states. Use caution because these
121 * module states are not normalized. Sometimes, a user input may cause one of
122 * the module speeds to go above the attainable max velocity. Use the
123 * DesaturateWheelSpeeds(wpi::array<SwerveModuleState, NumModules>*,
124 * units::meters_per_second_t) function to rectify this issue. In addition,
125 * you can leverage the power of C++17 to directly assign the module states to
126 * variables:
127 *
128 * @code{.cpp}
129 * auto [fl, fr, bl, br] = kinematics.ToSwerveModuleStates(chassisSpeeds);
130 * @endcode
131 */
133 const ChassisSpeeds& chassisSpeeds,
134 const Translation2d& centerOfRotation = Translation2d{}) const;
135
136 /**
137 * Performs forward kinematics to return the resulting chassis state from the
138 * given module states. This method is often used for odometry -- determining
139 * the robot's position on the field using data from the real-world speed and
140 * angle of each module on the robot.
141 *
142 * @param wheelStates The state of the modules (as a SwerveModuleState type)
143 * as measured from respective encoders and gyros. The order of the swerve
144 * module states should be same as passed into the constructor of this class.
145 *
146 * @return The resulting chassis speed.
147 */
148 template <typename... ModuleStates>
149 ChassisSpeeds ToChassisSpeeds(ModuleStates&&... wheelStates) const;
150
151 /**
152 * Performs forward kinematics to return the resulting chassis state from the
153 * given module states. This method is often used for odometry -- determining
154 * the robot's position on the field using data from the real-world speed and
155 * angle of each module on the robot.
156 *
157 * @param moduleStates The state of the modules as an wpi::array of type
158 * SwerveModuleState, NumModules long as measured from respective encoders
159 * and gyros. The order of the swerve module states should be same as passed
160 * into the constructor of this class.
161 *
162 * @return The resulting chassis speed.
163 */
166
167 /**
168 * Performs forward kinematics to return the resulting Twist2d from the
169 * given module position deltas. This method is often used for odometry --
170 * determining the robot's position on the field using data from the
171 * real-world position delta and angle of each module on the robot.
172 *
173 * @param wheelDeltas The latest change in position of the modules (as a
174 * SwerveModulePosition type) as measured from respective encoders and gyros.
175 * The order of the swerve module states should be same as passed into the
176 * constructor of this class.
177 *
178 * @return The resulting Twist2d.
179 */
180 template <typename... ModuleDeltas>
181 Twist2d ToTwist2d(ModuleDeltas&&... wheelDeltas) const;
182
183 /**
184 * Performs forward kinematics to return the resulting Twist2d from the
185 * given module position deltas. This method is often used for odometry --
186 * determining the robot's position on the field using data from the
187 * real-world position delta and angle of each module on the robot.
188 *
189 * @param wheelDeltas The latest change in position of the modules (as a
190 * SwerveModulePosition type) as measured from respective encoders and gyros.
191 * The order of the swerve module states should be same as passed into the
192 * constructor of this class.
193 *
194 * @return The resulting Twist2d.
195 */
198
199 /**
200 * Renormalizes the wheel speeds if any individual speed is above the
201 * specified maximum.
202 *
203 * Sometimes, after inverse kinematics, the requested speed
204 * from one or more modules may be above the max attainable speed for the
205 * driving motor on that module. To fix this issue, one can reduce all the
206 * wheel speeds to make sure that all requested module speeds are at-or-below
207 * the absolute threshold, while maintaining the ratio of speeds between
208 * modules.
209 *
210 * @param moduleStates Reference to array of module states. The array will be
211 * mutated with the normalized speeds!
212 * @param attainableMaxSpeed The absolute max speed that a module can reach.
213 */
214 static void DesaturateWheelSpeeds(
216 units::meters_per_second_t attainableMaxSpeed);
217
218 /**
219 * Renormalizes the wheel speeds if any individual speed is above the
220 * specified maximum, as well as getting rid of joystick saturation at edges
221 * of joystick.
222 *
223 * Sometimes, after inverse kinematics, the requested speed
224 * from one or more modules may be above the max attainable speed for the
225 * driving motor on that module. To fix this issue, one can reduce all the
226 * wheel speeds to make sure that all requested module speeds are at-or-below
227 * the absolute threshold, while maintaining the ratio of speeds between
228 * modules.
229 *
230 * @param moduleStates Reference to array of module states. The array will be
231 * mutated with the normalized speeds!
232 * @param currentChassisSpeed Current speed of the robot
233 * @param attainableMaxModuleSpeed The absolute max speed a module can reach
234 * @param attainableMaxRobotTranslationSpeed The absolute max speed the robot
235 * can reach while translating
236 * @param attainableMaxRobotRotationSpeed The absolute max speed the robot can
237 * reach while rotating
238 */
239 static void DesaturateWheelSpeeds(
241 ChassisSpeeds currentChassisSpeed,
242 units::meters_per_second_t attainableMaxModuleSpeed,
243 units::meters_per_second_t attainableMaxRobotTranslationSpeed,
244 units::radians_per_second_t attainableMaxRobotRotationSpeed);
245
246 private:
247 mutable Matrixd<NumModules * 2, 3> m_inverseKinematics;
250 mutable wpi::array<SwerveModuleState, NumModules> m_moduleStates;
251
252 mutable Translation2d m_previousCoR;
253};
254
255extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
256 SwerveDriveKinematics<4>;
257
258} // namespace frc
259
#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 module ...
Definition: SwerveDriveKinematics.h:47
wpi::array< SwerveModuleState, NumModules > ToSwerveModuleStates(const ChassisSpeeds &chassisSpeeds, const Translation2d &centerOfRotation=Translation2d{}) const
Performs inverse kinematics to return the module states from a desired chassis velocity.
Definition: SwerveDriveKinematics.inc:22
SwerveDriveKinematics(const SwerveDriveKinematics &)=default
ChassisSpeeds ToChassisSpeeds(ModuleStates &&... wheelStates) const
Performs forward kinematics to return the resulting chassis state from the given module states.
Definition: SwerveDriveKinematics.inc:69
Twist2d ToTwist2d(ModuleDeltas &&... wheelDeltas) const
Performs forward kinematics to return the resulting Twist2d from the given module position deltas.
Definition: SwerveDriveKinematics.inc:101
SwerveDriveKinematics(Translation2d wheel, Wheels &&... wheels)
Constructs a swerve drive kinematics object.
Definition: SwerveDriveKinematics.h:63
static void DesaturateWheelSpeeds(wpi::array< SwerveModuleState, NumModules > *moduleStates, units::meters_per_second_t attainableMaxSpeed)
Renormalizes the wheel speeds if any individual speed is above the specified maximum.
Definition: SwerveDriveKinematics.inc:133
SwerveDriveKinematics(const wpi::array< Translation2d, NumModules > &wheels)
Definition: SwerveDriveKinematics.h:82
Represents a translation in 2D space.
Definition: Translation2d.h:29
Definition: core.h:1240
This class is a wrapper around std::array that does compile time size checking.
Definition: array.h:25
static void ReportUsage(MathUsageId id, int count)
Definition: MathShared.h:73
Definition: AprilTagFieldLayout.h:22
template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) LinearQuadraticRegulator< 1
/file This file defines the SmallVector class.
Definition: AprilTagFieldLayout.h:18
constexpr empty_array_t empty_array
Definition: array.h:15
Represents the speed of a robot chassis.
Definition: ChassisSpeeds.h:25
A change in distance along a 2D arc since the last pose update.
Definition: Twist2d.h:21