32template <
size_t NumModules>
34 :
public Odometry<wpi::array<SwerveModuleState, NumModules>,
35 wpi::array<SwerveModulePosition, NumModules>> {
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Class for odometry.
Definition: Odometry.h:28
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition: SwerveDriveKinematics.h:52
Class for swerve drive odometry.
Definition: SwerveDriveOdometry.h:35
SwerveDriveOdometry(SwerveDriveKinematics< NumModules > kinematics, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose=Pose2d{})
Constructs a SwerveDriveOdometry object.
Definition: SwerveDriveOdometry.inc:12
Definition: AprilTagDetector_cv.h:11
template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) LinearQuadraticRegulator< 1