32template <
size_t NumModules>
35 wpi::util::array<SwerveModulePosition, NumModules>,
36 wpi::util::array<SwerveModuleVelocity, NumModules>,
37 wpi::util::array<SwerveModuleAcceleration, NumModules>> {
62 modulePositions, initialPose,
63 {0.1, 0.1, 0.1, 0.1}, {0.9, 0.9, 0.9, 0.9}} {
91 kinematics, m_odometryImpl, stateStdDevs, visionMeasurementStdDevs),
92 m_odometryImpl{kinematics, gyroAngle, modulePositions, initialPose} {
101 SwerveDrivePoseEstimator3d<4>;
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:94
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.hpp:28
PoseEstimator3d(Kinematics< wpi::util::array< SwerveModulePosition, NumModules >, wpi::util::array< SwerveModuleVelocity, NumModules >, wpi::util::array< SwerveModuleAcceleration, NumModules > > &kinematics, Odometry3d< wpi::util::array< SwerveModulePosition, NumModules >, wpi::util::array< SwerveModuleVelocity, NumModules >, wpi::util::array< SwerveModuleAcceleration, NumModules > > &odometry, const wpi::util::array< double, 4 > &stateStdDevs, const wpi::util::array< double, 4 > &visionMeasurementStdDevs)
Definition PoseEstimator3d.hpp:71
void ResetPose(const Pose3d &pose)
Definition PoseEstimator3d.hpp:143
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.hpp:69
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 SwerveDriveOdometry3d.hpp:32
SwerveDrivePoseEstimator3d(SwerveDriveKinematics< NumModules > &kinematics, const Rotation3d &gyroAngle, const wpi::util::array< SwerveModulePosition, NumModules > &modulePositions, const Pose3d &initialPose)
Constructs a SwerveDrivePoseEstimator3d with default standard deviations for the model and vision mea...
Definition SwerveDrivePoseEstimator3d.hpp:56
SwerveDrivePoseEstimator3d(SwerveDriveKinematics< NumModules > &kinematics, const Rotation3d &gyroAngle, const wpi::util::array< SwerveModulePosition, NumModules > &modulePositions, const Pose3d &initialPose, const wpi::util::array< double, 4 > &stateStdDevs, const wpi::util::array< double, 4 > &visionMeasurementStdDevs)
Constructs a SwerveDrivePoseEstimator3d.
Definition SwerveDrivePoseEstimator3d.hpp:83
This class is a wrapper around std::array that does compile time size checking.
Definition array.hpp:26
Definition LinearSystem.hpp:20