WPILibC++ 2027.0.0-alpha-2
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
81 wpi::math::MathSharedStore::ReportUsage("SwerveDriveKinematics", "");
82 }
83
86 : m_modules{modules}, m_moduleHeadings(wpi::empty_array) {
87 for (size_t i = 0; i < NumModules; i++) {
88 // clang-format off
89 m_inverseKinematics.template block<2, 3>(i * 2, 0) <<
90 1, 0, (-m_modules[i].Y()).value(),
91 0, 1, (+m_modules[i].X()).value();
92 // clang-format on
93 }
94
95 m_forwardKinematics = m_inverseKinematics.householderQr();
96
97 wpi::math::MathSharedStore::ReportUsage("Kinematics_SwerveDrive", "");
98 }
99
101
102 /**
103 * Reset the internal swerve module headings.
104 * @param moduleHeadings The swerve module headings. The order of the module
105 * headings should be same as passed into the constructor of this class.
106 */
107 template <std::convertible_to<Rotation2d>... ModuleHeadings>
108 requires(sizeof...(ModuleHeadings) == NumModules)
109 void ResetHeadings(ModuleHeadings&&... moduleHeadings) {
110 return this->ResetHeadings(
111 wpi::array<Rotation2d, NumModules>{moduleHeadings...});
112 }
113
114 /**
115 * Reset the internal swerve module headings.
116 * @param moduleHeadings The swerve module headings. The order of the module
117 * headings should be same as passed into the constructor of this class.
118 */
120 for (size_t i = 0; i < NumModules; i++) {
121 m_moduleHeadings[i] = moduleHeadings[i];
122 }
123 }
124
125 /**
126 * Performs inverse kinematics to return the module states from a desired
127 * chassis velocity. This method is often used to convert joystick values into
128 * module speeds and angles.
129 *
130 * This function also supports variable centers of rotation. During normal
131 * operations, the center of rotation is usually the same as the physical
132 * center of the robot; therefore, the argument is defaulted to that use case.
133 * However, if you wish to change the center of rotation for evasive
134 * maneuvers, vision alignment, or for any other use case, you can do so.
135 *
136 * In the case that the desired chassis speeds are zero (i.e. the robot will
137 * be stationary), the previously calculated module angle will be maintained.
138 *
139 * @param chassisSpeeds The desired chassis speed.
140 * @param centerOfRotation The center of rotation. For example, if you set the
141 * center of rotation at one corner of the robot and provide a chassis speed
142 * that only has a dtheta component, the robot will rotate around that corner.
143 *
144 * @return An array containing the module states. Use caution because these
145 * module states are not normalized. Sometimes, a user input may cause one of
146 * the module speeds to go above the attainable max velocity. Use the
147 * DesaturateWheelSpeeds(wpi::array<SwerveModuleState, NumModules>*,
148 * units::meters_per_second_t) function to rectify this issue. In addition,
149 * you can leverage the power of C++17 to directly assign the module states to
150 * variables:
151 *
152 * @code{.cpp}
153 * auto [fl, fr, bl, br] = kinematics.ToSwerveModuleStates(chassisSpeeds);
154 * @endcode
155 */
157 const ChassisSpeeds& chassisSpeeds,
158 const Translation2d& centerOfRotation = Translation2d{}) const {
160
161 if (chassisSpeeds.vx == 0_mps && chassisSpeeds.vy == 0_mps &&
162 chassisSpeeds.omega == 0_rad_per_s) {
163 for (size_t i = 0; i < NumModules; i++) {
164 moduleStates[i] = {0_mps, m_moduleHeadings[i]};
165 }
166
167 return moduleStates;
168 }
169
170 // We have a new center of rotation. We need to compute the matrix again.
171 if (centerOfRotation != m_previousCoR) {
172 for (size_t i = 0; i < NumModules; i++) {
173 // clang-format off
174 m_inverseKinematics.template block<2, 3>(i * 2, 0) =
176 {1, 0, (-m_modules[i].Y() + centerOfRotation.Y()).value()},
177 {0, 1, (+m_modules[i].X() - centerOfRotation.X()).value()}};
178 // clang-format on
179 }
180 m_previousCoR = centerOfRotation;
181 }
182
183 Eigen::Vector3d chassisSpeedsVector{chassisSpeeds.vx.value(),
184 chassisSpeeds.vy.value(),
185 chassisSpeeds.omega.value()};
186
187 Matrixd<NumModules * 2, 1> moduleStateMatrix =
188 m_inverseKinematics * chassisSpeedsVector;
189
190 for (size_t i = 0; i < NumModules; i++) {
191 units::meters_per_second_t x{moduleStateMatrix(i * 2, 0)};
192 units::meters_per_second_t y{moduleStateMatrix(i * 2 + 1, 0)};
193
194 auto speed = units::math::hypot(x, y);
195 auto rotation = speed > 1e-6_mps ? Rotation2d{x.value(), y.value()}
196 : m_moduleHeadings[i];
197
198 moduleStates[i] = {speed, rotation};
199 m_moduleHeadings[i] = rotation;
200 }
201
202 return moduleStates;
203 }
204
206 const ChassisSpeeds& chassisSpeeds) const override {
207 return ToSwerveModuleStates(chassisSpeeds);
208 }
209
210 /**
211 * Performs forward kinematics to return the resulting chassis state from the
212 * given module states. This method is often used for odometry -- determining
213 * the robot's position on the field using data from the real-world speed and
214 * angle of each module on the robot.
215 *
216 * @param moduleStates The state of the modules (as a SwerveModuleState type)
217 * as measured from respective encoders and gyros. The order of the swerve
218 * module states should be same as passed into the constructor of this class.
219 *
220 * @return The resulting chassis speed.
221 */
222 template <std::convertible_to<SwerveModuleState>... ModuleStates>
223 requires(sizeof...(ModuleStates) == NumModules)
224 ChassisSpeeds ToChassisSpeeds(ModuleStates&&... moduleStates) const {
225 return this->ToChassisSpeeds(
227 }
228
229 /**
230 * Performs forward kinematics to return the resulting chassis state from the
231 * given module states. This method is often used for odometry -- determining
232 * the robot's position on the field using data from the real-world speed and
233 * angle of each module on the robot.
234 *
235 * @param moduleStates The state of the modules as an wpi::array of type
236 * SwerveModuleState, NumModules long as measured from respective encoders
237 * and gyros. The order of the swerve module states should be same as passed
238 * into the constructor of this class.
239 *
240 * @return The resulting chassis speed.
241 */
243 moduleStates) const override {
244 Matrixd<NumModules * 2, 1> moduleStateMatrix;
245
246 for (size_t i = 0; i < NumModules; ++i) {
247 SwerveModuleState module = moduleStates[i];
248 moduleStateMatrix(i * 2, 0) = module.speed.value() * module.angle.Cos();
249 moduleStateMatrix(i * 2 + 1, 0) =
250 module.speed.value() * module.angle.Sin();
251 }
252
253 Eigen::Vector3d chassisSpeedsVector =
254 m_forwardKinematics.solve(moduleStateMatrix);
255
256 return {units::meters_per_second_t{chassisSpeedsVector(0)},
257 units::meters_per_second_t{chassisSpeedsVector(1)},
258 units::radians_per_second_t{chassisSpeedsVector(2)}};
259 }
260
261 /**
262 * Performs forward kinematics to return the resulting Twist2d from the
263 * given module position deltas. This method is often used for odometry --
264 * determining the robot's position on the field using data from the
265 * real-world position delta and angle of each module on the robot.
266 *
267 * @param moduleDeltas The latest change in position of the modules (as a
268 * SwerveModulePosition type) as measured from respective encoders and gyros.
269 * The order of the swerve module states should be same as passed into the
270 * constructor of this class.
271 *
272 * @return The resulting Twist2d.
273 */
274 template <std::convertible_to<SwerveModulePosition>... ModuleDeltas>
275 requires(sizeof...(ModuleDeltas) == NumModules)
276 Twist2d ToTwist2d(ModuleDeltas&&... moduleDeltas) const {
277 return this->ToTwist2d(
279 }
280
281 /**
282 * Performs forward kinematics to return the resulting Twist2d from the
283 * given module position deltas. This method is often used for odometry --
284 * determining the robot's position on the field using data from the
285 * real-world position delta and angle of each module on the robot.
286 *
287 * @param moduleDeltas The latest change in position of the modules (as a
288 * SwerveModulePosition type) as measured from respective encoders and gyros.
289 * The order of the swerve module states should be same as passed into the
290 * constructor of this class.
291 *
292 * @return The resulting Twist2d.
293 */
296 Matrixd<NumModules * 2, 1> moduleDeltaMatrix;
297
298 for (size_t i = 0; i < NumModules; ++i) {
299 SwerveModulePosition module = moduleDeltas[i];
300 moduleDeltaMatrix(i * 2, 0) =
301 module.distance.value() * module.angle.Cos();
302 moduleDeltaMatrix(i * 2 + 1, 0) =
303 module.distance.value() * module.angle.Sin();
304 }
305
306 Eigen::Vector3d chassisDeltaVector =
307 m_forwardKinematics.solve(moduleDeltaMatrix);
308
309 return {units::meter_t{chassisDeltaVector(0)},
310 units::meter_t{chassisDeltaVector(1)},
311 units::radian_t{chassisDeltaVector(2)}};
312 }
313
316 const wpi::array<SwerveModulePosition, NumModules>& end) const override {
317 auto result =
319 for (size_t i = 0; i < NumModules; i++) {
320 result[i] = {end[i].distance - start[i].distance, end[i].angle};
321 }
322 return ToTwist2d(result);
323 }
324
325 /**
326 * Renormalizes the wheel speeds if any individual speed is above the
327 * specified maximum.
328 *
329 * Sometimes, after inverse kinematics, the requested speed
330 * from one or more modules may be above the max attainable speed for the
331 * driving motor on that module. To fix this issue, one can reduce all the
332 * wheel speeds to make sure that all requested module speeds are at-or-below
333 * the absolute threshold, while maintaining the ratio of speeds between
334 * modules.
335 *
336 * Scaling down the module speeds rotates the direction of net motion in the
337 * opposite direction of rotational velocity, which makes discretizing the
338 * chassis speeds inaccurate because the discretization did not account for
339 * this translational skew.
340 *
341 * @param moduleStates Reference to array of module states. The array will be
342 * mutated with the normalized speeds!
343 * @param attainableMaxSpeed The absolute max speed that a module can reach.
344 */
347 units::meters_per_second_t attainableMaxSpeed) {
348 auto& states = *moduleStates;
349 auto realMaxSpeed =
350 units::math::abs(std::max_element(states.begin(), states.end(),
351 [](const auto& a, const auto& b) {
352 return units::math::abs(a.speed) <
353 units::math::abs(b.speed);
354 })
355 ->speed);
356
357 if (realMaxSpeed > attainableMaxSpeed) {
358 for (auto& module : states) {
359 module.speed = module.speed / realMaxSpeed * attainableMaxSpeed;
360 }
361 }
362 }
363
364 /**
365 * Renormalizes the wheel speeds if any individual speed is above the
366 * specified maximum, as well as getting rid of joystick saturation at edges
367 * of joystick.
368 *
369 * Sometimes, after inverse kinematics, the requested speed
370 * from one or more modules may be above the max attainable speed for the
371 * driving motor on that module. To fix this issue, one can reduce all the
372 * wheel speeds to make sure that all requested module speeds are at-or-below
373 * the absolute threshold, while maintaining the ratio of speeds between
374 * modules.
375 *
376 * Scaling down the module speeds rotates the direction of net motion in the
377 * opposite direction of rotational velocity, which makes discretizing the
378 * chassis speeds inaccurate because the discretization did not account for
379 * this translational skew.
380 *
381 * @param moduleStates Reference to array of module states. The array will be
382 * mutated with the normalized speeds!
383 * @param desiredChassisSpeed The desired speed of the robot
384 * @param attainableMaxModuleSpeed The absolute max speed a module can reach
385 * @param attainableMaxRobotTranslationSpeed The absolute max speed the robot
386 * can reach while translating
387 * @param attainableMaxRobotRotationSpeed The absolute max speed the robot can
388 * reach while rotating
389 */
392 ChassisSpeeds desiredChassisSpeed,
393 units::meters_per_second_t attainableMaxModuleSpeed,
394 units::meters_per_second_t attainableMaxRobotTranslationSpeed,
395 units::radians_per_second_t attainableMaxRobotRotationSpeed) {
396 auto& states = *moduleStates;
397
398 auto realMaxSpeed =
399 units::math::abs(std::max_element(states.begin(), states.end(),
400 [](const auto& a, const auto& b) {
401 return units::math::abs(a.speed) <
402 units::math::abs(b.speed);
403 })
404 ->speed);
405
406 if (attainableMaxRobotTranslationSpeed == 0_mps ||
407 attainableMaxRobotRotationSpeed == 0_rad_per_s ||
408 realMaxSpeed == 0_mps) {
409 return;
410 }
411
412 auto translationalK =
413 units::math::hypot(desiredChassisSpeed.vx, desiredChassisSpeed.vy) /
414 attainableMaxRobotTranslationSpeed;
415
416 auto rotationalK = units::math::abs(desiredChassisSpeed.omega) /
417 attainableMaxRobotRotationSpeed;
418
419 auto k = units::math::max(translationalK, rotationalK);
420
421 auto scale = units::math::min(k * attainableMaxModuleSpeed / realMaxSpeed,
422 units::scalar_t{1});
423 for (auto& module : states) {
424 module.speed = module.speed * scale;
425 }
426 }
427
431 double t) const override {
432 auto result =
434 for (size_t i = 0; i < NumModules; ++i) {
435 result[i] = start[i].Interpolate(end[i], t);
436 }
437 return {result};
438 }
439
441 return m_modules;
442 }
443
444 private:
446 mutable Matrixd<NumModules * 2, 3> m_inverseKinematics;
447 Eigen::HouseholderQR<Matrixd<NumModules * 2, 3>> m_forwardKinematics;
448 mutable wpi::array<Rotation2d, NumModules> m_moduleHeadings;
449
450 mutable Translation2d m_previousCoR;
451};
452
453template <typename ModuleTranslation, typename... ModuleTranslations>
454SwerveDriveKinematics(ModuleTranslation, ModuleTranslations...)
455 -> SwerveDriveKinematics<1 + sizeof...(ModuleTranslations)>;
456
457extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
459
460} // namespace frc
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.h:94
#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 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:156
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:428
const wpi::array< Translation2d, NumModules > & GetModules() const
Definition SwerveDriveKinematics.h:440
SwerveDriveKinematics(const SwerveDriveKinematics &)=default
void ResetHeadings(ModuleHeadings &&... moduleHeadings)
Reset the internal swerve module headings.
Definition SwerveDriveKinematics.h:109
void ResetHeadings(wpi::array< Rotation2d, NumModules > moduleHeadings)
Reset the internal swerve module headings.
Definition SwerveDriveKinematics.h:119
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:242
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:345
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:276
SwerveDriveKinematics(const wpi::array< Translation2d, NumModules > &modules)
Definition SwerveDriveKinematics.h:84
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:205
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:390
ChassisSpeeds ToChassisSpeeds(ModuleStates &&... moduleStates) const
Performs forward kinematics to return the resulting chassis state from the given module states.
Definition SwerveDriveKinematics.h:224
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:294
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:314
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(std::string_view resource, std::string_view data)
Definition MathShared.h:61
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 SystemServer.h:9
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
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