24#include "wpi/units/math.hpp"
25#include "wpi/units/velocity.hpp"
54template <
size_t NumModules>
57 wpi::util::array<SwerveModulePosition, NumModules>,
58 wpi::util::array<SwerveModuleVelocity, NumModules>,
59 wpi::util::array<SwerveModuleAcceleration, NumModules>> {
72 template <std::convertible_to<Translation2d>... ModuleTranslations>
73 requires(
sizeof...(ModuleTranslations) == NumModules)
75 : m_modules{moduleTranslations...},
77 for (
size_t i = 0; i < NumModules; i++) {
79 m_firstOrderInverseKinematics.template block<2, 3>(i * 2, 0) <<
80 1, 0, (-m_modules[i].Y()).value(),
81 0, 1, (+m_modules[i].X()).value();
83 m_secondOrderInverseKinematics.template block<2, 4>(i * 2, 0) <<
84 1, 0, (-m_modules[i].X()).value(), (-m_modules[i].Y()).value(),
85 0, 1, (-m_modules[i].Y()).value(), (+m_modules[i].X()).value();
89 m_firstOrderForwardKinematics =
90 m_firstOrderInverseKinematics.householderQr();
91 m_secondOrderForwardKinematics =
92 m_secondOrderInverseKinematics.householderQr();
99 : m_modules{modules}, m_moduleHeadings(
wpi::
util::empty_array) {
100 for (
size_t i = 0; i < NumModules; i++) {
102 m_firstOrderInverseKinematics.template block<2, 3>(i * 2, 0) <<
103 1, 0, (-m_modules[i].Y()).value(),
104 0, 1, (+m_modules[i].X()).value();
106 m_secondOrderInverseKinematics.template block<2, 4>(i * 2, 0) <<
107 1, 0, (-m_modules[i].X()).value(), (-m_modules[i].Y()).value(),
108 0, 1, (-m_modules[i].Y()).value(), (+m_modules[i].X()).value();
112 m_firstOrderForwardKinematics =
113 m_firstOrderInverseKinematics.householderQr();
114 m_secondOrderForwardKinematics =
115 m_secondOrderInverseKinematics.householderQr();
128 template <std::convertible_to<Rotation2d>... ModuleHeadings>
129 requires(
sizeof...(ModuleHeadings) == NumModules)
142 for (
size_t i = 0; i < NumModules; i++) {
143 m_moduleHeadings[i] = moduleHeadings[i];
186 if (chassisVelocities.
vx == 0_mps && chassisVelocities.
vy == 0_mps &&
187 chassisVelocities.
omega == 0_rad_per_s) {
188 for (
size_t i = 0; i < NumModules; i++) {
189 moduleVelocities[i] = {0_mps, m_moduleHeadings[i]};
192 return moduleVelocities;
196 if (centerOfRotation != m_previousCoR) {
197 SetInverseKinematics(centerOfRotation);
200 Eigen::Vector3d chassisVelocitiesVector{chassisVelocities.
vx.value(),
201 chassisVelocities.
vy.value(),
202 chassisVelocities.
omega.value()};
205 m_firstOrderInverseKinematics * chassisVelocitiesVector;
207 for (
size_t i = 0; i < NumModules; i++) {
208 wpi::units::meters_per_second_t x{moduleVelocityMatrix(i * 2, 0)};
209 wpi::units::meters_per_second_t y{moduleVelocityMatrix(i * 2 + 1, 0)};
211 auto velocity = wpi::units::math::hypot(x, y);
212 auto rotation = velocity > 1e-6_mps ? Rotation2d{x.value(), y.value()}
213 : m_moduleHeadings[i];
215 moduleVelocities[i] = {velocity, rotation};
216 m_moduleHeadings[i] = rotation;
219 return moduleVelocities;
239 template <std::convertible_to<SwerveModuleVelocity>... ModuleVelocities>
240 requires(
sizeof...(ModuleVelocities) == NumModules)
242 ModuleVelocities&&... moduleVelocities)
const {
245 moduleVelocities...});
262 moduleVelocities)
const override {
265 for (
size_t i = 0; i < NumModules; ++i) {
267 moduleVelocityMatrix(i * 2, 0) =
268 module.velocity.value() * module.angle.Cos();
269 moduleVelocityMatrix(i * 2 + 1, 0) =
270 module.velocity.value() * module.angle.Sin();
273 Eigen::Vector3d chassisVelocitiesVector =
274 m_firstOrderForwardKinematics.solve(moduleVelocityMatrix);
276 return {wpi::units::meters_per_second_t{chassisVelocitiesVector(0)},
277 wpi::units::meters_per_second_t{chassisVelocitiesVector(1)},
278 wpi::units::radians_per_second_t{chassisVelocitiesVector(2)}};
293 template <std::convertible_to<SwerveModulePosition>... ModuleDeltas>
294 requires(
sizeof...(ModuleDeltas) == NumModules)
316 for (
size_t i = 0; i < NumModules; ++i) {
318 moduleDeltaMatrix(i * 2, 0) =
319 module.distance.value() * module.angle.Cos();
320 moduleDeltaMatrix(i * 2 + 1, 0) =
321 module.distance.value() * module.angle.Sin();
324 Eigen::Vector3d chassisDeltaVector =
325 m_firstOrderForwardKinematics.solve(moduleDeltaMatrix);
327 return {wpi::units::meter_t{chassisDeltaVector(0)},
328 wpi::units::meter_t{chassisDeltaVector(1)},
329 wpi::units::radian_t{chassisDeltaVector(2)}};
338 for (
size_t i = 0; i < NumModules; i++) {
339 result[i] = {end[i].distance - start[i].distance, end[i].angle};
369 wpi::units::meters_per_second_t attainableMaxVelocity) {
370 auto realMaxVelocity = wpi::units::math::abs(
371 std::max_element(moduleVelocities.begin(), moduleVelocities.end(),
372 [](
const auto& a,
const auto& b) {
373 return wpi::units::math::abs(a.velocity) <
374 wpi::units::math::abs(b.velocity);
378 if (realMaxVelocity > attainableMaxVelocity) {
381 for (
size_t i = 0; i < NumModules; ++i) {
382 velocities[i] = {moduleVelocities[i].velocity / realMaxVelocity *
383 attainableMaxVelocity,
384 moduleVelocities[i].angle};
388 return moduleVelocities;
423 wpi::units::meters_per_second_t attainableMaxModuleVelocity,
424 wpi::units::meters_per_second_t attainableMaxRobotTranslationVelocity,
425 wpi::units::radians_per_second_t attainableMaxRobotRotationVelocity) {
426 auto realMaxVelocity = wpi::units::math::abs(
427 std::max_element(moduleVelocities.begin(), moduleVelocities.end(),
428 [](
const auto& a,
const auto& b) {
429 return wpi::units::math::abs(a.velocity) <
430 wpi::units::math::abs(b.velocity);
434 if (attainableMaxRobotTranslationVelocity == 0_mps ||
435 attainableMaxRobotRotationVelocity == 0_rad_per_s ||
436 realMaxVelocity == 0_mps) {
437 return moduleVelocities;
440 auto translationalK = wpi::units::math::hypot(desiredChassisVelocity.
vx,
441 desiredChassisVelocity.
vy) /
442 attainableMaxRobotTranslationVelocity;
444 auto rotationalK = wpi::units::math::abs(desiredChassisVelocity.
omega) /
445 attainableMaxRobotRotationVelocity;
447 auto k = wpi::units::math::max(translationalK, rotationalK);
450 wpi::units::math::min(k * attainableMaxModuleVelocity / realMaxVelocity,
451 wpi::units::scalar_t{1});
454 for (
size_t i = 0; i < NumModules; ++i) {
455 velocities[i] = {moduleVelocities[i].velocity * scale,
456 moduleVelocities[i].angle};
464 double t)
const override {
467 for (
size_t i = 0; i < NumModules; ++i) {
468 result[i] = start[i].Interpolate(end[i], t);
500 const units::radians_per_second_t angularVelocity = 0.0_rad_per_s,
509 if (chassisAccelerations.
ax == 0.0_mps_sq &&
510 chassisAccelerations.
ay == 0.0_mps_sq &&
511 chassisAccelerations.
alpha == 0.0_rad_per_s_sq) {
512 for (
size_t i = 0; i < NumModules; i++) {
513 moduleAccelerations[i] = {0.0_mps_sq,
Rotation2d{0.0_rad}};
515 return moduleAccelerations;
518 if (centerOfRotation != m_previousCoR) {
519 SetInverseKinematics(centerOfRotation);
522 Eigen::Vector4d chassisAccelerationsVector{
523 chassisAccelerations.
ax.value(), chassisAccelerations.
ay.value(),
524 angularVelocity.value() * angularVelocity.value(),
525 chassisAccelerations.
alpha.value()};
528 m_secondOrderInverseKinematics * chassisAccelerationsVector;
530 for (
size_t i = 0; i < NumModules; i++) {
531 units::meters_per_second_squared_t x{moduleAccelerationsMatrix(i * 2, 0)};
532 units::meters_per_second_squared_t y{
533 moduleAccelerationsMatrix(i * 2 + 1, 0)};
538 units::meters_per_second_squared_t linearAcceleration =
539 units::math::hypot(x, y);
541 if (linearAcceleration.value() < 1e-6) {
542 moduleAccelerations[i] = {linearAcceleration, {}};
544 moduleAccelerations[i] = {linearAcceleration,
545 Rotation2d{x.value(), y.value()}};
549 return moduleAccelerations;
579 std::convertible_to<SwerveModuleAcceleration>... ModuleAccelerations>
580 requires(
sizeof...(ModuleAccelerations) == NumModules)
582 ModuleAccelerations&&... moduleAccelerations)
const {
585 moduleAccelerations...});
602 moduleAccelerations)
const override {
609 for (
size_t i = 0; i < NumModules; i++) {
612 moduleAccelerationsMatrix(i * 2 + 0, 0) =
613 module.acceleration.value() * module.angle.Cos();
614 moduleAccelerationsMatrix(i * 2 + 1, 0) =
615 module.acceleration.value() * module.angle.Sin();
618 Eigen::Vector4d chassisAccelerationsVector =
619 m_secondOrderForwardKinematics.solve(moduleAccelerationsMatrix);
623 return {units::meters_per_second_squared_t{chassisAccelerationsVector(0)},
624 units::meters_per_second_squared_t{chassisAccelerationsVector(1)},
625 units::radians_per_second_squared_t{chassisAccelerationsVector(3)}};
631 Eigen::HouseholderQR<Matrixd<NumModules * 2, 3>>
632 m_firstOrderForwardKinematics;
634 Eigen::HouseholderQR<Matrixd<NumModules * 2, 4>>
635 m_secondOrderForwardKinematics;
648 void SetInverseKinematics(
const Translation2d& centerOfRotation)
const {
649 for (
size_t i = 0; i < NumModules; i++) {
650 const double rx = m_modules[i].X().value() - centerOfRotation.
X().value();
651 const double ry = m_modules[i].Y().value() - centerOfRotation.
Y().value();
653 m_firstOrderInverseKinematics.row(i * 2 + 0) << 1, 0, -ry;
654 m_firstOrderInverseKinematics.row(i * 2 + 1) << 0, 1, rx;
656 m_secondOrderInverseKinematics.row(i * 2 + 0) << 1, 0, -rx, -ry;
657 m_secondOrderInverseKinematics.row(i * 2 + 1) << 0, 1, -ry, +rx;
659 m_previousCoR = centerOfRotation;
663template <
typename ModuleTranslation,
typename... ModuleTranslations>
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:94
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel v...
Definition Kinematics.hpp:26
static void ReportUsage(std::string_view resource, std::string_view data)
Definition MathShared.hpp:61
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:29
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition SwerveDriveKinematics.hpp:59
void ResetHeadings(ModuleHeadings &&... moduleHeadings)
Reset the internal swerve module headings.
Definition SwerveDriveKinematics.hpp:130
wpi::util::array< SwerveModuleAcceleration, NumModules > ToWheelAccelerations(const ChassisAccelerations &chassisAccelerations) const override
Performs inverse kinematics to return the module accelerations from a desired chassis acceleration.
Definition SwerveDriveKinematics.hpp:561
wpi::util::array< SwerveModuleVelocity, NumModules > ToWheelVelocities(const ChassisVelocities &chassisVelocities) const override
Performs inverse kinematics to return the wheel velocities from a desired chassis velocity.
Definition SwerveDriveKinematics.hpp:222
wpi::util::array< SwerveModuleAcceleration, NumModules > ToSwerveModuleAccelerations(const ChassisAccelerations &chassisAccelerations, const units::radians_per_second_t angularVelocity=0.0_rad_per_s, const Translation2d ¢erOfRotation=Translation2d{}) const
Performs inverse kinematics to return the module accelerations from a desired chassis acceleration.
Definition SwerveDriveKinematics.hpp:498
SwerveDriveKinematics(const wpi::util::array< Translation2d, NumModules > &modules)
Definition SwerveDriveKinematics.hpp:97
SwerveDriveKinematics(const SwerveDriveKinematics &)=default
const wpi::util::array< Translation2d, NumModules > & GetModules() const
Definition SwerveDriveKinematics.hpp:473
SwerveDriveKinematics(ModuleTranslations &&... moduleTranslations)
Constructs a swerve drive kinematics object.
Definition SwerveDriveKinematics.hpp:74
Twist2d ToTwist2d(wpi::util::array< SwerveModulePosition, NumModules > moduleDeltas) const
Performs forward kinematics to return the resulting Twist2d from the given module position deltas.
Definition SwerveDriveKinematics.hpp:312
Twist2d ToTwist2d(const wpi::util::array< SwerveModulePosition, NumModules > &start, const wpi::util::array< SwerveModulePosition, NumModules > &end) const override
Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions.
Definition SwerveDriveKinematics.hpp:332
ChassisVelocities ToChassisVelocities(const wpi::util::array< SwerveModuleVelocity, NumModules > &moduleVelocities) const override
Performs forward kinematics to return the resulting chassis state from the given module states.
Definition SwerveDriveKinematics.hpp:260
static wpi::util::array< SwerveModuleVelocity, NumModules > DesaturateWheelVelocities(wpi::util::array< SwerveModuleVelocity, NumModules > moduleVelocities, ChassisVelocities desiredChassisVelocity, wpi::units::meters_per_second_t attainableMaxModuleVelocity, wpi::units::meters_per_second_t attainableMaxRobotTranslationVelocity, wpi::units::radians_per_second_t attainableMaxRobotRotationVelocity)
Renormalizes the wheel velocities if any individual velocity is above the specified maximum,...
Definition SwerveDriveKinematics.hpp:420
Twist2d ToTwist2d(ModuleDeltas &&... moduleDeltas) const
Performs forward kinematics to return the resulting Twist2d from the given module position deltas.
Definition SwerveDriveKinematics.hpp:295
wpi::util::array< SwerveModulePosition, NumModules > Interpolate(const wpi::util::array< SwerveModulePosition, NumModules > &start, const wpi::util::array< SwerveModulePosition, NumModules > &end, double t) const override
Performs interpolation between two values.
Definition SwerveDriveKinematics.hpp:461
ChassisVelocities ToChassisVelocities(ModuleVelocities &&... moduleVelocities) const
Performs forward kinematics to return the resulting chassis state from the given module states.
Definition SwerveDriveKinematics.hpp:241
static wpi::util::array< SwerveModuleVelocity, NumModules > DesaturateWheelVelocities(wpi::util::array< SwerveModuleVelocity, NumModules > moduleVelocities, wpi::units::meters_per_second_t attainableMaxVelocity)
Renormalizes the wheel velocities if any individual velocity is above the specified maximum.
Definition SwerveDriveKinematics.hpp:367
ChassisAccelerations ToChassisAccelerations(ModuleAccelerations &&... moduleAccelerations) const
Performs forward kinematics to return the resulting chassis accelerations from the given module accel...
Definition SwerveDriveKinematics.hpp:581
ChassisAccelerations ToChassisAccelerations(const wpi::util::array< SwerveModuleAcceleration, NumModules > &moduleAccelerations) const override
Performs forward kinematics to return the resulting chassis accelerations from the given module accel...
Definition SwerveDriveKinematics.hpp:600
wpi::util::array< SwerveModuleVelocity, NumModules > ToSwerveModuleVelocities(const ChassisVelocities &chassisVelocities, const Translation2d ¢erOfRotation=Translation2d{}) const
Performs inverse kinematics to return the module states from a desired chassis velocity.
Definition SwerveDriveKinematics.hpp:180
void ResetHeadings(wpi::util::array< Rotation2d, NumModules > moduleHeadings)
Reset the internal swerve module headings.
Definition SwerveDriveKinematics.hpp:141
Represents a translation in 2D space.
Definition Translation2d.hpp:33
constexpr wpi::units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation2d.hpp:112
constexpr wpi::units::meter_t X() const
Returns the X component of the translation.
Definition Translation2d.hpp:105
This class is a wrapper around std::array that does compile time size checking.
Definition array.hpp:26
Definition LinearSystem.hpp:20
SwerveDriveKinematics(ModuleTranslation, ModuleTranslations...) -> SwerveDriveKinematics< 1+sizeof...(ModuleTranslations)>
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.hpp:21
Definition raw_os_ostream.hpp:19
constexpr empty_array_t empty_array
Definition array.hpp:16
Definition CvSource.hpp:15
Represents robot chassis accelerations.
Definition ChassisAccelerations.hpp:21
units::meters_per_second_squared_t ax
Acceleration along the x-axis.
Definition ChassisAccelerations.hpp:25
units::radians_per_second_squared_t alpha
Angular acceleration of the robot frame.
Definition ChassisAccelerations.hpp:35
units::meters_per_second_squared_t ay
Acceleration along the y-axis.
Definition ChassisAccelerations.hpp:30
Represents robot chassis velocities.
Definition ChassisVelocities.hpp:26
wpi::units::meters_per_second_t vx
Velocity along the x-axis.
Definition ChassisVelocities.hpp:30
wpi::units::radians_per_second_t omega
Represents the angular velocity of the robot frame.
Definition ChassisVelocities.hpp:40
wpi::units::meters_per_second_t vy
Velocity along the y-axis.
Definition ChassisVelocities.hpp:35
Represents the accelerations of one swerve module.
Definition SwerveModuleAcceleration.hpp:16
Represents the position of one swerve module.
Definition SwerveModulePosition.hpp:17
Represents the velocity of one swerve module.
Definition SwerveModuleVelocity.hpp:17
A change in distance along a 2D arc since the last pose update.
Definition Twist2d.hpp:23