32template <
size_t NumModules>
 
   34    : 
public Odometry3d<wpi::array<SwerveModuleState, NumModules>,
 
   35                        wpi::array<SwerveModulePosition, NumModules>> {
 
   45#if defined(__GNUC__) && !defined(__clang__) 
   46#pragma GCC diagnostic push 
   47#pragma GCC diagnostic ignored "-Wmaybe-uninitialized" 
   54                                          modulePositions, initialPose),
 
   55        m_kinematicsImpl(kinematics) {
 
 
   59#if defined(__GNUC__) && !defined(__clang__) 
   60#pragma GCC diagnostic pop 
 
   68    SwerveDriveOdometry3d<4>;
 
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:92
Class for odometry.
Definition Odometry3d.h:33
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.h:28
A rotation in a 3D coordinate frame represented by a quaternion.
Definition Rotation3d.h:29
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition SwerveDriveKinematics.h:54
Class for swerve drive odometry.
Definition SwerveDriveOdometry3d.h:35
SwerveDriveOdometry3d(SwerveDriveKinematics< NumModules > kinematics, const Rotation3d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose3d &initialPose=Pose3d{})
Constructs a SwerveDriveOdometry3d object.
Definition SwerveDriveOdometry3d.h:49
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:75
SwerveDriveKinematics(ModuleTranslation, ModuleTranslations...) -> SwerveDriveKinematics< 1+sizeof...(ModuleTranslations)>