28template <
size_t NumModules>
53template <
size_t NumModules>
55 :
public Kinematics<SwerveDriveWheelSpeeds<NumModules>,
56 SwerveDriveWheelPositions<NumModules>> {
69 template <std::convertible_to<Translation2d>... ModuleTranslations>
70 requires(
sizeof...(ModuleTranslations) == NumModules)
72 : m_modules{moduleTranslations...}, m_moduleHeadings(
wpi::empty_array) {
73 for (
size_t i = 0; i < NumModules; i++) {
75 m_inverseKinematics.template block<2, 3>(i * 2, 0) <<
76 1, 0, (-m_modules[i].Y()).value(),
77 0, 1, (+m_modules[i].X()).value();
81 m_forwardKinematics = m_inverseKinematics.householderQr();
89 : m_modules{modules}, m_moduleHeadings(
wpi::empty_array) {
90 for (
size_t i = 0; i < NumModules; i++) {
92 m_inverseKinematics.template block<2, 3>(i * 2, 0) <<
93 1, 0, (-m_modules[i].Y()).value(),
94 0, 1, (+m_modules[i].X()).value();
98 m_forwardKinematics = m_inverseKinematics.householderQr();
111 template <std::convertible_to<Rotation2d>... ModuleHeadings>
112 requires(
sizeof...(ModuleHeadings) == NumModules)
177 template <std::convertible_to<SwerveModuleState>... ModuleStates>
178 requires(
sizeof...(ModuleStates) == NumModules)
198 moduleStates)
const override;
213 template <std::convertible_to<SwerveModulePosition>... ModuleDeltas>
214 requires(
sizeof...(ModuleDeltas) == NumModules)
241 for (
size_t i = 0; i < NumModules; i++) {
242 auto startModule = start.positions[i];
244 result[i] = {endModule.distance - startModule.distance, endModule.angle};
266 units::meters_per_second_t attainableMaxSpeed);
292 units::meters_per_second_t attainableMaxModuleSpeed,
293 units::meters_per_second_t attainableMaxRobotTranslationSpeed,
294 units::radians_per_second_t attainableMaxRobotRotationSpeed);
298 Eigen::HouseholderQR<Matrixd<NumModules * 2, 3>> m_forwardKinematics;
306 SwerveDriveKinematics<4>;
#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:23
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition: SwerveDriveKinematics.h:56
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:30
SwerveDriveKinematics(const SwerveDriveKinematics &)=default
void ResetHeadings(ModuleHeadings &&... moduleHeadings)
Reset the internal swerve module headings.
Definition: SwerveDriveKinematics.h:113
SwerveDriveWheelSpeeds< NumModules > ToWheelSpeeds(const ChassisSpeeds &chassisSpeeds) const override
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.
Definition: SwerveDriveKinematics.h:160
SwerveDriveKinematics(ModuleTranslations &&... moduleTranslations)
Constructs a swerve drive kinematics object.
Definition: SwerveDriveKinematics.h:71
Twist2d ToTwist2d(const SwerveDriveWheelPositions< NumModules > &start, const SwerveDriveWheelPositions< NumModules > &end) const override
Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions.
Definition: SwerveDriveKinematics.h:236
Twist2d ToTwist2d(ModuleDeltas &&... moduleDeltas) const
Performs forward kinematics to return the resulting Twist2d from the given module position deltas.
Definition: SwerveDriveKinematics.h:215
SwerveDriveKinematics(const wpi::array< Translation2d, NumModules > &modules)
Definition: SwerveDriveKinematics.h:87
ChassisSpeeds ToChassisSpeeds(ModuleStates &&... moduleStates) const
Performs forward kinematics to return the resulting chassis state from the given module states.
Definition: SwerveDriveKinematics.h:179
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:118
Represents a translation in 2D space.
Definition: Translation2d.h:27
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:73
Definition: AprilTagPoseEstimator.h:15
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition: EigenCore.h:21
template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) LinearQuadraticRegulator< 1
@ kKinematics_SwerveDrive
Definition: ntcore_cpp.h:26
Represents the speed of a robot chassis.
Definition: ChassisSpeeds.h:25
Represents the wheel positions for a swerve drive drivetrain.
Definition: SwerveDriveWheelPositions.h:18
wpi::array< SwerveModulePosition, NumModules > positions
The distances driven by the wheels.
Definition: SwerveDriveWheelPositions.h:22
A change in distance along a 2D arc since the last pose update.
Definition: Twist2d.h:21
constexpr empty_array_t empty_array
Definition: array.h:16