WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
frc::SwerveDrivePoseEstimator< NumModules > Class Template Reference

This class wraps Swerve Drive Odometry to fuse latency-compensated vision measurements with swerve drive encoder distance measurements. More...

#include <frc/estimator/SwerveDrivePoseEstimator.h>

Inheritance diagram for frc::SwerveDrivePoseEstimator< NumModules >:
frc::PoseEstimator< wpi::array< SwerveModuleState, NumModules >, wpi::array< SwerveModulePosition, NumModules > >

Public Member Functions

 SwerveDrivePoseEstimator (SwerveDriveKinematics< NumModules > &kinematics, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose)
 Constructs a SwerveDrivePoseEstimator with default standard deviations for the model and vision measurements.
 
 SwerveDrivePoseEstimator (SwerveDriveKinematics< NumModules > &kinematics, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose, const wpi::array< double, 3 > &stateStdDevs, const wpi::array< double, 3 > &visionMeasurementStdDevs)
 Constructs a SwerveDrivePoseEstimator.
 
- Public Member Functions inherited from frc::PoseEstimator< wpi::array< SwerveModuleState, NumModules >, wpi::array< SwerveModulePosition, NumModules > >
 PoseEstimator (Kinematics< wpi::array< SwerveModuleState, NumModules >, wpi::array< SwerveModulePosition, NumModules > > &kinematics, Odometry< wpi::array< SwerveModuleState, NumModules >, wpi::array< SwerveModulePosition, NumModules > > &odometry, const wpi::array< double, 3 > &stateStdDevs, const wpi::array< double, 3 > &visionMeasurementStdDevs)
 Constructs a PoseEstimator.
 
void SetVisionMeasurementStdDevs (const wpi::array< double, 3 > &visionMeasurementStdDevs)
 Sets the pose estimator's trust in vision measurements.
 
void ResetPosition (const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &wheelPositions, const Pose2d &pose)
 Resets the robot's position on the field.
 
void ResetPose (const Pose2d &pose)
 Resets the robot's pose.
 
void ResetTranslation (const Translation2d &translation)
 Resets the robot's translation.
 
void ResetRotation (const Rotation2d &rotation)
 Resets the robot's rotation.
 
Pose2d GetEstimatedPosition () const
 Gets the estimated robot pose.
 
std::optional< Pose2dSampleAt (units::second_t timestamp) const
 Return the pose at a given timestamp, if the buffer is not empty.
 
void AddVisionMeasurement (const Pose2d &visionRobotPose, units::second_t timestamp)
 Adds a vision measurement to the Kalman Filter.
 
void AddVisionMeasurement (const Pose2d &visionRobotPose, units::second_t timestamp, const wpi::array< double, 3 > &visionMeasurementStdDevs)
 Adds a vision measurement to the Kalman Filter.
 
Pose2d Update (const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &wheelPositions)
 Updates the pose estimator with wheel encoder and gyro information.
 
Pose2d UpdateWithTime (units::second_t currentTime, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &wheelPositions)
 Updates the pose estimator with wheel encoder and gyro information.
 

Detailed Description

template<size_t NumModules>
class frc::SwerveDrivePoseEstimator< NumModules >

This class wraps Swerve Drive Odometry to fuse latency-compensated vision measurements with swerve drive encoder distance measurements.

It is intended to be a drop-in for SwerveDriveOdometry.

Update() should be called every robot loop.

AddVisionMeasurement() can be called as infrequently as you want; if you never call it, then this class will behave as regular encoder odometry.

Constructor & Destructor Documentation

◆ SwerveDrivePoseEstimator() [1/2]

template<size_t NumModules>
frc::SwerveDrivePoseEstimator< NumModules >::SwerveDrivePoseEstimator ( SwerveDriveKinematics< NumModules > & kinematics,
const Rotation2d & gyroAngle,
const wpi::array< SwerveModulePosition, NumModules > & modulePositions,
const Pose2d & initialPose )
inline

Constructs a SwerveDrivePoseEstimator with default standard deviations for the model and vision measurements.

The default standard deviations of the model states are 0.1 meters for x, 0.1 meters for y, and 0.1 radians for heading. The default standard deviations of the vision measurements are 0.9 meters for x, 0.9 meters for y, and 0.9 radians for heading.

Parameters
kinematicsA correctly-configured kinematics object for your drivetrain.
gyroAngleThe current gyro angle.
modulePositionsThe current distance and rotation measurements of the swerve modules.
initialPoseThe starting pose estimate.

◆ SwerveDrivePoseEstimator() [2/2]

template<size_t NumModules>
frc::SwerveDrivePoseEstimator< NumModules >::SwerveDrivePoseEstimator ( SwerveDriveKinematics< NumModules > & kinematics,
const Rotation2d & gyroAngle,
const wpi::array< SwerveModulePosition, NumModules > & modulePositions,
const Pose2d & initialPose,
const wpi::array< double, 3 > & stateStdDevs,
const wpi::array< double, 3 > & visionMeasurementStdDevs )
inline

Constructs a SwerveDrivePoseEstimator.

Parameters
kinematicsA correctly-configured kinematics object for your drivetrain.
gyroAngleThe current gyro angle.
modulePositionsThe current distance and rotation measurements of the swerve modules.
initialPoseThe starting pose estimate.
stateStdDevsStandard deviations of the pose estimate (x position in meters, y position in meters, and heading in radians). Increase these numbers to trust your state estimate less.
visionMeasurementStdDevsStandard deviations of the vision pose measurement (x position in meters, y position in meters, and heading in radians). Increase these numbers to trust the vision pose measurement less.

The documentation for this class was generated from the following file: