51template <
size_t NumModules>
53 :
public Kinematics<wpi::array<SwerveModuleState, NumModules>,
54 wpi::array<SwerveModulePosition, NumModules>> {
67 template <std::convertible_to<Translation2d>... ModuleTranslations>
68 requires(
sizeof...(ModuleTranslations) == NumModules)
71 for (
size_t i = 0; i < NumModules; i++) {
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();
79 m_forwardKinematics = m_inverseKinematics.householderQr();
86 : m_modules{modules}, m_moduleHeadings(
wpi::empty_array) {
87 for (
size_t i = 0; i < NumModules; i++) {
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();
95 m_forwardKinematics = m_inverseKinematics.householderQr();
107 template <std::convertible_to<Rotation2d>... ModuleHeadings>
108 requires(
sizeof...(ModuleHeadings) == NumModules)
120 for (
size_t i = 0; i < NumModules; i++) {
121 m_moduleHeadings[i] = moduleHeadings[i];
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]};
171 if (centerOfRotation != m_previousCoR) {
172 for (
size_t i = 0; i < NumModules; i++) {
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()}};
180 m_previousCoR = centerOfRotation;
183 Eigen::Vector3d chassisSpeedsVector{chassisSpeeds.
vx.value(),
184 chassisSpeeds.
vy.value(),
185 chassisSpeeds.
omega.value()};
188 m_inverseKinematics * chassisSpeedsVector;
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)};
195 auto rotation = speed > 1e-6_mps ? Rotation2d{x.value(), y.value()}
196 : m_moduleHeadings[i];
198 moduleStates[i] = {speed, rotation};
199 m_moduleHeadings[i] = rotation;
222 template <std::convertible_to<SwerveModuleState>... ModuleStates>
223 requires(
sizeof...(ModuleStates) == NumModules)
243 moduleStates)
const override {
246 for (
size_t i = 0; i < NumModules; ++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();
253 Eigen::Vector3d chassisSpeedsVector =
254 m_forwardKinematics.solve(moduleStateMatrix);
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)}};
274 template <std::convertible_to<SwerveModulePosition>... ModuleDeltas>
275 requires(
sizeof...(ModuleDeltas) == NumModules)
298 for (
size_t i = 0; i < NumModules; ++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();
306 Eigen::Vector3d chassisDeltaVector =
307 m_forwardKinematics.solve(moduleDeltaMatrix);
309 return {units::meter_t{chassisDeltaVector(0)},
310 units::meter_t{chassisDeltaVector(1)},
311 units::radian_t{chassisDeltaVector(2)}};
319 for (
size_t i = 0; i < NumModules; i++) {
320 result[i] = {end[i].distance - start[i].distance, end[i].angle};
347 units::meters_per_second_t attainableMaxSpeed) {
348 auto& states = *moduleStates;
351 [](
const auto& a,
const auto& b) {
352 return units::math::abs(a.speed) <
353 units::math::abs(b.speed);
357 if (realMaxSpeed > attainableMaxSpeed) {
358 for (
auto& module : states) {
359 module.speed = module.speed / realMaxSpeed * attainableMaxSpeed;
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;
400 [](
const auto& a,
const auto& b) {
401 return units::math::abs(a.speed) <
402 units::math::abs(b.speed);
406 if (attainableMaxRobotTranslationSpeed == 0_mps ||
407 attainableMaxRobotRotationSpeed == 0_rad_per_s ||
408 realMaxSpeed == 0_mps) {
412 auto translationalK =
414 attainableMaxRobotTranslationSpeed;
417 attainableMaxRobotRotationSpeed;
423 for (
auto& module : states) {
424 module.speed = module.speed * scale;
431 double t)
const override {
434 for (
size_t i = 0; i < NumModules; ++i) {
435 result[i] = start[i].Interpolate(end[i], t);
447 Eigen::HouseholderQR<Matrixd<NumModules * 2, 3>> m_forwardKinematics;
453template <
typename ModuleTranslation,
typename... ModuleTranslations>
#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 ¢erOfRotation=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