28template <
size_t NumModules>
30 :
public Odometry<wpi::util::array<SwerveModulePosition, NumModules>,
31 wpi::util::array<SwerveModuleVelocity, NumModules>,
32 wpi::util::array<SwerveModuleAcceleration, NumModules>> {
47 modulePositions, initialPose),
48 m_kinematicsImpl(kinematics) {
57 SwerveDriveOdometry<4>;
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:94
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
static void ReportUsage(std::string_view resource, std::string_view data)
Definition MathShared.hpp:61
Class for odometry.
Definition Odometry.hpp:31
Odometry(const Kinematics< wpi::util::array< SwerveModulePosition, NumModules >, wpi::util::array< SwerveModuleVelocity, NumModules >, wpi::util::array< SwerveModuleAcceleration, NumModules > > &kinematics, const Rotation2d &gyroAngle, const wpi::util::array< SwerveModulePosition, NumModules > &wheelPositions, const Pose2d &initialPose=Pose2d{})
Definition Odometry.hpp:41
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition SwerveDriveKinematics.hpp:59
Class for swerve drive odometry.
Definition SwerveDriveOdometry.hpp:32
SwerveDriveOdometry(SwerveDriveKinematics< NumModules > kinematics, const Rotation2d &gyroAngle, const wpi::util::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose=Pose2d{})
Constructs a SwerveDriveOdometry object.
Definition SwerveDriveOdometry.hpp:42
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)>