WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
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 <algorithm>
8#include <concepts>
9#include <cstddef>
10
11#include <Eigen/QR>
12#include <wpi/SymbolExports.h>
13#include <wpi/array.h>
14
15#include "frc/EigenCore.h"
23#include "units/math.h"
24#include "units/velocity.h"
25#include "wpimath/MathShared.h"
26
27namespace frc {
28
29/**
30 * Helper class that converts a chassis velocity (dx, dy, and dtheta components)
31 * into individual module states (speed and angle).
32 *
33 * The inverse kinematics (converting from a desired chassis velocity to
34 * individual module states) uses the relative locations of the modules with
35 * respect to the center of rotation. The center of rotation for inverse
36 * kinematics is also variable. This means that you can set your set your center
37 * of rotation in a corner of the robot to perform special evasion maneuvers.
38 *
39 * Forward kinematics (converting an array of module states into the overall
40 * chassis motion) is performs the exact opposite of what inverse kinematics
41 * does. Since this is an overdetermined system (more equations than variables),
42 * we use a least-squares approximation.
43 *
44 * The inverse kinematics: [moduleStates] = [moduleLocations] * [chassisSpeeds]
45 * We take the Moore-Penrose pseudoinverse of [moduleLocations] and then
46 * multiply by [moduleStates] to get our chassis speeds.
47 *
48 * Forward kinematics is also used for odometry -- determining the position of
49 * the robot on the field using encoders and a gyro.
50 */
51template <size_t NumModules>
53 : public Kinematics<wpi::array<SwerveModuleState, NumModules>,
54 wpi::array<SwerveModulePosition, NumModules>> {
55 public:
56 /**
57 * Constructs a swerve drive kinematics object. This takes in a variable
58 * number of module locations as Translation2ds. The order in which you pass
59 * in the module locations is the same order that you will receive the module
60 * states when performing inverse kinematics. It is also expected that you
61 * pass in the module states in the same order when calling the forward
62 * kinematics methods.
63 *
64 * @param moduleTranslations The locations of the modules relative to the
65 * physical center of the robot.
66 */
67 template <std::convertible_to<Translation2d>... ModuleTranslations>
68 requires(sizeof...(ModuleTranslations) == NumModules)
69 explicit SwerveDriveKinematics(ModuleTranslations&&... moduleTranslations)
70 : m_modules{moduleTranslations...}, m_moduleHeadings(wpi::empty_array) {
71 for (size_t i = 0; i < NumModules; i++) {
72 // clang-format off
73 m_inverseKinematics.template block<2, 3>(i * 2, 0) <<
74 1, 0, (-m_modules[i].Y()).value(),
75 0, 1, (+m_modules[i].X()).value();
76 // clang-format on
77 }
78
79 m_forwardKinematics = m_inverseKinematics.householderQr();
80
83 }
84
87 : m_modules{modules}, m_moduleHeadings(wpi::empty_array) {
88 for (size_t i = 0; i < NumModules; i++) {
89 // clang-format off
90 m_inverseKinematics.template block<2, 3>(i * 2, 0) <<
91 1, 0, (-m_modules[i].Y()).value(),
92 0, 1, (+m_modules[i].X()).value();
93 // clang-format on
94 }
95
96 m_forwardKinematics = m_inverseKinematics.householderQr();
97
100 }
101
103
104 /**
105 * Reset the internal swerve module headings.
106 * @param moduleHeadings The swerve module headings. The order of the module
107 * headings should be same as passed into the constructor of this class.
108 */
109 template <std::convertible_to<Rotation2d>... ModuleHeadings>
110 requires(sizeof...(ModuleHeadings) == NumModules)
111 void ResetHeadings(ModuleHeadings&&... moduleHeadings) {
112 return this->ResetHeadings(
113 wpi::array<Rotation2d, NumModules>{moduleHeadings...});
114 }
115
116 /**
117 * Reset the internal swerve module headings.
118 * @param moduleHeadings The swerve module headings. The order of the module
119 * headings should be same as passed into the constructor of this class.
120 */
122 for (size_t i = 0; i < NumModules; i++) {
123 m_moduleHeadings[i] = moduleHeadings[i];
124 }
125 }
126
127 /**
128 * Performs inverse kinematics to return the module states from a desired
129 * chassis velocity. This method is often used to convert joystick values into
130 * module speeds and angles.
131 *
132 * This function also supports variable centers of rotation. During normal
133 * operations, the center of rotation is usually the same as the physical
134 * center of the robot; therefore, the argument is defaulted to that use case.
135 * However, if you wish to change the center of rotation for evasive
136 * maneuvers, vision alignment, or for any other use case, you can do so.
137 *
138 * In the case that the desired chassis speeds are zero (i.e. the robot will
139 * be stationary), the previously calculated module angle will be maintained.
140 *
141 * @param chassisSpeeds The desired chassis speed.
142 * @param centerOfRotation The center of rotation. For example, if you set the
143 * center of rotation at one corner of the robot and provide a chassis speed
144 * that only has a dtheta component, the robot will rotate around that corner.
145 *
146 * @return An array containing the module states. Use caution because these
147 * module states are not normalized. Sometimes, a user input may cause one of
148 * the module speeds to go above the attainable max velocity. Use the
149 * DesaturateWheelSpeeds(wpi::array<SwerveModuleState, NumModules>*,
150 * units::meters_per_second_t) function to rectify this issue. In addition,
151 * you can leverage the power of C++17 to directly assign the module states to
152 * variables:
153 *
154 * @code{.cpp}
155 * auto [fl, fr, bl, br] = kinematics.ToSwerveModuleStates(chassisSpeeds);
156 * @endcode
157 */
159 const ChassisSpeeds& chassisSpeeds,
160 const Translation2d& centerOfRotation = Translation2d{}) const {
162
163 if (chassisSpeeds.vx == 0_mps && chassisSpeeds.vy == 0_mps &&
164 chassisSpeeds.omega == 0_rad_per_s) {
165 for (size_t i = 0; i < NumModules; i++) {
166 moduleStates[i] = {0_mps, m_moduleHeadings[i]};
167 }
168
169 return moduleStates;
170 }
171
172 // We have a new center of rotation. We need to compute the matrix again.
173 if (centerOfRotation != m_previousCoR) {
174 for (size_t i = 0; i < NumModules; i++) {
175 // clang-format off
176 m_inverseKinematics.template block<2, 3>(i * 2, 0) =
178 {1, 0, (-m_modules[i].Y() + centerOfRotation.Y()).value()},
179 {0, 1, (+m_modules[i].X() - centerOfRotation.X()).value()}};
180 // clang-format on
181 }
182 m_previousCoR = centerOfRotation;
183 }
184
185 Eigen::Vector3d chassisSpeedsVector{chassisSpeeds.vx.value(),
186 chassisSpeeds.vy.value(),
187 chassisSpeeds.omega.value()};
188
189 Matrixd<NumModules * 2, 1> moduleStateMatrix =
190 m_inverseKinematics * chassisSpeedsVector;
191
192 for (size_t i = 0; i < NumModules; i++) {
193 units::meters_per_second_t x{moduleStateMatrix(i * 2, 0)};
194 units::meters_per_second_t y{moduleStateMatrix(i * 2 + 1, 0)};
195
196 auto speed = units::math::hypot(x, y);
197 auto rotation = speed > 1e-6_mps ? Rotation2d{x.value(), y.value()}
198 : m_moduleHeadings[i];
199
200 moduleStates[i] = {speed, rotation};
201 m_moduleHeadings[i] = rotation;
202 }
203
204 return moduleStates;
205 }
206
208 const ChassisSpeeds& chassisSpeeds) const override {
209 return ToSwerveModuleStates(chassisSpeeds);
210 }
211
212 /**
213 * Performs forward kinematics to return the resulting chassis state from the
214 * given module states. This method is often used for odometry -- determining
215 * the robot's position on the field using data from the real-world speed and
216 * angle of each module on the robot.
217 *
218 * @param moduleStates The state of the modules (as a SwerveModuleState type)
219 * as measured from respective encoders and gyros. The order of the swerve
220 * module states should be same as passed into the constructor of this class.
221 *
222 * @return The resulting chassis speed.
223 */
224 template <std::convertible_to<SwerveModuleState>... ModuleStates>
225 requires(sizeof...(ModuleStates) == NumModules)
226 ChassisSpeeds ToChassisSpeeds(ModuleStates&&... moduleStates) const {
227 return this->ToChassisSpeeds(
229 }
230
231 /**
232 * Performs forward kinematics to return the resulting chassis state from the
233 * given module states. This method is often used for odometry -- determining
234 * the robot's position on the field using data from the real-world speed and
235 * angle of each module on the robot.
236 *
237 * @param moduleStates The state of the modules as an wpi::array of type
238 * SwerveModuleState, NumModules long as measured from respective encoders
239 * and gyros. The order of the swerve module states should be same as passed
240 * into the constructor of this class.
241 *
242 * @return The resulting chassis speed.
243 */
245 moduleStates) const override {
246 Matrixd<NumModules * 2, 1> moduleStateMatrix;
247
248 for (size_t i = 0; i < NumModules; ++i) {
249 SwerveModuleState module = moduleStates[i];
250 moduleStateMatrix(i * 2, 0) = module.speed.value() * module.angle.Cos();
251 moduleStateMatrix(i * 2 + 1, 0) =
252 module.speed.value() * module.angle.Sin();
253 }
254
255 Eigen::Vector3d chassisSpeedsVector =
256 m_forwardKinematics.solve(moduleStateMatrix);
257
258 return {units::meters_per_second_t{chassisSpeedsVector(0)},
259 units::meters_per_second_t{chassisSpeedsVector(1)},
260 units::radians_per_second_t{chassisSpeedsVector(2)}};
261 }
262
263 /**
264 * Performs forward kinematics to return the resulting Twist2d from the
265 * given module position deltas. This method is often used for odometry --
266 * determining the robot's position on the field using data from the
267 * real-world position delta and angle of each module on the robot.
268 *
269 * @param moduleDeltas The latest change in position of the modules (as a
270 * SwerveModulePosition type) as measured from respective encoders and gyros.
271 * The order of the swerve module states should be same as passed into the
272 * constructor of this class.
273 *
274 * @return The resulting Twist2d.
275 */
276 template <std::convertible_to<SwerveModulePosition>... ModuleDeltas>
277 requires(sizeof...(ModuleDeltas) == NumModules)
278 Twist2d ToTwist2d(ModuleDeltas&&... moduleDeltas) const {
279 return this->ToTwist2d(
281 }
282
283 /**
284 * Performs forward kinematics to return the resulting Twist2d from the
285 * given module position deltas. This method is often used for odometry --
286 * determining the robot's position on the field using data from the
287 * real-world position delta and angle of each module on the robot.
288 *
289 * @param moduleDeltas The latest change in position of the modules (as a
290 * SwerveModulePosition type) as measured from respective encoders and gyros.
291 * The order of the swerve module states should be same as passed into the
292 * constructor of this class.
293 *
294 * @return The resulting Twist2d.
295 */
298 Matrixd<NumModules * 2, 1> moduleDeltaMatrix;
299
300 for (size_t i = 0; i < NumModules; ++i) {
301 SwerveModulePosition module = moduleDeltas[i];
302 moduleDeltaMatrix(i * 2, 0) =
303 module.distance.value() * module.angle.Cos();
304 moduleDeltaMatrix(i * 2 + 1, 0) =
305 module.distance.value() * module.angle.Sin();
306 }
307
308 Eigen::Vector3d chassisDeltaVector =
309 m_forwardKinematics.solve(moduleDeltaMatrix);
310
311 return {units::meter_t{chassisDeltaVector(0)},
312 units::meter_t{chassisDeltaVector(1)},
313 units::radian_t{chassisDeltaVector(2)}};
314 }
315
318 const wpi::array<SwerveModulePosition, NumModules>& end) const override {
319 auto result =
321 for (size_t i = 0; i < NumModules; i++) {
322 result[i] = {end[i].distance - start[i].distance, end[i].angle};
323 }
324 return ToTwist2d(result);
325 }
326
327 /**
328 * Renormalizes the wheel speeds if any individual speed is above the
329 * specified maximum.
330 *
331 * Sometimes, after inverse kinematics, the requested speed
332 * from one or more modules may be above the max attainable speed for the
333 * driving motor on that module. To fix this issue, one can reduce all the
334 * wheel speeds to make sure that all requested module speeds are at-or-below
335 * the absolute threshold, while maintaining the ratio of speeds between
336 * modules.
337 *
338 * @param moduleStates Reference to array of module states. The array will be
339 * mutated with the normalized speeds!
340 * @param attainableMaxSpeed The absolute max speed that a module can reach.
341 */
344 units::meters_per_second_t attainableMaxSpeed) {
345 auto& states = *moduleStates;
346 auto realMaxSpeed =
347 units::math::abs(std::max_element(states.begin(), states.end(),
348 [](const auto& a, const auto& b) {
349 return units::math::abs(a.speed) <
350 units::math::abs(b.speed);
351 })
352 ->speed);
353
354 if (realMaxSpeed > attainableMaxSpeed) {
355 for (auto& module : states) {
356 module.speed = module.speed / realMaxSpeed * attainableMaxSpeed;
357 }
358 }
359 }
360
361 /**
362 * Renormalizes the wheel speeds if any individual speed is above the
363 * specified maximum, as well as getting rid of joystick saturation at edges
364 * of joystick.
365 *
366 * Sometimes, after inverse kinematics, the requested speed
367 * from one or more modules may be above the max attainable speed for the
368 * driving motor on that module. To fix this issue, one can reduce all the
369 * wheel speeds to make sure that all requested module speeds are at-or-below
370 * the absolute threshold, while maintaining the ratio of speeds between
371 * modules.
372 *
373 * @param moduleStates Reference to array of module states. The array will be
374 * mutated with the normalized speeds!
375 * @param desiredChassisSpeed The desired speed of the robot
376 * @param attainableMaxModuleSpeed The absolute max speed a module can reach
377 * @param attainableMaxRobotTranslationSpeed The absolute max speed the robot
378 * can reach while translating
379 * @param attainableMaxRobotRotationSpeed The absolute max speed the robot can
380 * reach while rotating
381 */
384 ChassisSpeeds desiredChassisSpeed,
385 units::meters_per_second_t attainableMaxModuleSpeed,
386 units::meters_per_second_t attainableMaxRobotTranslationSpeed,
387 units::radians_per_second_t attainableMaxRobotRotationSpeed) {
388 auto& states = *moduleStates;
389
390 auto realMaxSpeed =
391 units::math::abs(std::max_element(states.begin(), states.end(),
392 [](const auto& a, const auto& b) {
393 return units::math::abs(a.speed) <
394 units::math::abs(b.speed);
395 })
396 ->speed);
397
398 if (attainableMaxRobotTranslationSpeed == 0_mps ||
399 attainableMaxRobotRotationSpeed == 0_rad_per_s ||
400 realMaxSpeed == 0_mps) {
401 return;
402 }
403
404 auto translationalK =
405 units::math::hypot(desiredChassisSpeed.vx, desiredChassisSpeed.vy) /
406 attainableMaxRobotTranslationSpeed;
407
408 auto rotationalK = units::math::abs(desiredChassisSpeed.omega) /
409 attainableMaxRobotRotationSpeed;
410
411 auto k = units::math::max(translationalK, rotationalK);
412
413 auto scale = units::math::min(k * attainableMaxModuleSpeed / realMaxSpeed,
414 units::scalar_t{1});
415 for (auto& module : states) {
416 module.speed = module.speed * scale;
417 }
418 }
419
423 double t) const override {
424 auto result =
426 for (size_t i = 0; i < NumModules; ++i) {
427 result[i] = start[i].Interpolate(end[i], t);
428 }
429 return {result};
430 }
431
433 return m_modules;
434 }
435
436 private:
438 mutable Matrixd<NumModules * 2, 3> m_inverseKinematics;
439 Eigen::HouseholderQR<Matrixd<NumModules * 2, 3>> m_forwardKinematics;
440 mutable wpi::array<Rotation2d, NumModules> m_moduleHeadings;
441
442 mutable Translation2d m_previousCoR;
443};
444
445template <typename ModuleTranslation, typename... ModuleTranslations>
446SwerveDriveKinematics(ModuleTranslation, ModuleTranslations...)
447 -> SwerveDriveKinematics<1 + sizeof...(ModuleTranslations)>;
448
449extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
451
452} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:92
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 module ...
Definition SwerveDriveKinematics.h:54
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.h:158
wpi::array< SwerveModulePosition, NumModules > Interpolate(const wpi::array< SwerveModulePosition, NumModules > &start, const wpi::array< SwerveModulePosition, NumModules > &end, double t) const override
Performs interpolation between two values.
Definition SwerveDriveKinematics.h:420
const wpi::array< Translation2d, NumModules > & GetModules() const
Definition SwerveDriveKinematics.h:432
SwerveDriveKinematics(const SwerveDriveKinematics &)=default
void ResetHeadings(ModuleHeadings &&... moduleHeadings)
Reset the internal swerve module headings.
Definition SwerveDriveKinematics.h:111
void ResetHeadings(wpi::array< Rotation2d, NumModules > moduleHeadings)
Reset the internal swerve module headings.
Definition SwerveDriveKinematics.h:121
ChassisSpeeds ToChassisSpeeds(const wpi::array< SwerveModuleState, NumModules > &moduleStates) const override
Performs forward kinematics to return the resulting chassis state from the given module states.
Definition SwerveDriveKinematics.h:244
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.h:342
SwerveDriveKinematics(ModuleTranslations &&... moduleTranslations)
Constructs a swerve drive kinematics object.
Definition SwerveDriveKinematics.h:69
Twist2d ToTwist2d(ModuleDeltas &&... moduleDeltas) const
Performs forward kinematics to return the resulting Twist2d from the given module position deltas.
Definition SwerveDriveKinematics.h:278
SwerveDriveKinematics(const wpi::array< Translation2d, NumModules > &modules)
Definition SwerveDriveKinematics.h:85
wpi::array< SwerveModuleState, NumModules > ToWheelSpeeds(const ChassisSpeeds &chassisSpeeds) const override
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.
Definition SwerveDriveKinematics.h:207
static void DesaturateWheelSpeeds(wpi::array< SwerveModuleState, NumModules > *moduleStates, ChassisSpeeds desiredChassisSpeed, units::meters_per_second_t attainableMaxModuleSpeed, units::meters_per_second_t attainableMaxRobotTranslationSpeed, units::radians_per_second_t attainableMaxRobotRotationSpeed)
Renormalizes the wheel speeds if any individual speed is above the specified maximum,...
Definition SwerveDriveKinematics.h:382
ChassisSpeeds ToChassisSpeeds(ModuleStates &&... moduleStates) const
Performs forward kinematics to return the resulting chassis state from the given module states.
Definition SwerveDriveKinematics.h:226
Twist2d ToTwist2d(wpi::array< SwerveModulePosition, NumModules > moduleDeltas) const
Performs forward kinematics to return the resulting Twist2d from the given module position deltas.
Definition SwerveDriveKinematics.h:296
Twist2d ToTwist2d(const wpi::array< SwerveModulePosition, NumModules > &start, const wpi::array< SwerveModulePosition, NumModules > &end) const override
Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions.
Definition SwerveDriveKinematics.h:316
Represents a translation in 2D space.
Definition Translation2d.h:29
Container for values which represent quantities of a given unit.
Definition base.h:1930
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
static void ReportUsage(MathUsageId id, int count)
Definition MathShared.h:75
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
constexpr UnitTypeLhs hypot(const UnitTypeLhs &x, const UnitTypeRhs &y)
Computes the square root of the sum-of-squares of x and y.
Definition math.h:508
Definition CAN.h:11
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
SwerveDriveKinematics(ModuleTranslation, ModuleTranslations...) -> SwerveDriveKinematics< 1+sizeof...(ModuleTranslations)>
constexpr UnitTypeLhs max(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs)
Definition base.h:3422
constexpr UnitTypeLhs min(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs)
Definition base.h:3414
Foonathan namespace.
Definition ntcore_cpp.h:26
constexpr empty_array_t empty_array
Definition array.h:16
Represents the speed of a robot chassis.
Definition ChassisSpeeds.h:25
units::meters_per_second_t vx
Velocity along the x-axis.
Definition ChassisSpeeds.h:29
units::meters_per_second_t vy
Velocity along the y-axis.
Definition ChassisSpeeds.h:34
units::radians_per_second_t omega
Represents the angular velocity of the robot frame.
Definition ChassisSpeeds.h:39
Represents the position of one swerve module.
Definition SwerveModulePosition.h:18
Represents the state of one swerve module.
Definition SwerveModuleState.h:18
A change in distance along a 2D arc since the last pose update.
Definition Twist2d.h:22