46template <
size_t NumModules>
62 template <
typename... Wheels>
65 static_assert(
sizeof...(wheels) >= 1,
66 "A swerve drive requires at least two modules");
68 for (
size_t i = 0; i < NumModules; i++) {
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();
76 m_forwardKinematics = m_inverseKinematics.householderQr();
85 for (
size_t i = 0; i < NumModules; i++) {
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();
93 m_forwardKinematics = m_inverseKinematics.householderQr();
148 template <
typename... ModuleStates>
180 template <
typename... ModuleDeltas>
216 units::meters_per_second_t attainableMaxSpeed);
242 units::meters_per_second_t attainableMaxModuleSpeed,
243 units::meters_per_second_t attainableMaxRobotTranslationSpeed,
244 units::radians_per_second_t attainableMaxRobotRotationSpeed);
256 SwerveDriveKinematics<4>;
#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 ¢erOfRotation=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
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
@ kKinematics_SwerveDrive
/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