WPILibC++ 2024.3.2
frc::MecanumDrivePoseEstimator Class Reference

This class wraps Mecanum Drive Odometry to fuse latency-compensated vision measurements with mecanum drive encoder velocity measurements. More...

#include <frc/estimator/MecanumDrivePoseEstimator.h>

Inheritance diagram for frc::MecanumDrivePoseEstimator:
frc::PoseEstimator< MecanumDriveWheelSpeeds, MecanumDriveWheelPositions >

Public Member Functions

 MecanumDrivePoseEstimator (MecanumDriveKinematics &kinematics, const Rotation2d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose2d &initialPose)
 Constructs a MecanumDrivePoseEstimator with default standard deviations for the model and vision measurements. More...
 
 MecanumDrivePoseEstimator (MecanumDriveKinematics &kinematics, const Rotation2d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose2d &initialPose, const wpi::array< double, 3 > &stateStdDevs, const wpi::array< double, 3 > &visionMeasurementStdDevs)
 Constructs a MecanumDrivePoseEstimator. More...
 
- Public Member Functions inherited from frc::PoseEstimator< MecanumDriveWheelSpeeds, MecanumDriveWheelPositions >
 PoseEstimator (Kinematics< MecanumDriveWheelSpeeds, WheelPositions > &kinematics, Odometry< MecanumDriveWheelSpeeds, WheelPositions > &odometry, const wpi::array< double, 3 > &stateStdDevs, const wpi::array< double, 3 > &visionMeasurementStdDevs)
 Constructs a PoseEstimator. More...
 
void SetVisionMeasurementStdDevs (const wpi::array< double, 3 > &visionMeasurementStdDevs)
 Sets the pose estimator's trust in vision measurements. More...
 
void ResetPosition (const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &pose)
 Resets the robot's position on the field. More...
 
Pose2d GetEstimatedPosition () const
 Gets the estimated robot pose. More...
 
void AddVisionMeasurement (const Pose2d &visionRobotPose, units::second_t timestamp)
 Adds a vision measurement to the Kalman Filter. More...
 
void AddVisionMeasurement (const Pose2d &visionRobotPose, units::second_t timestamp, const wpi::array< double, 3 > &visionMeasurementStdDevs)
 Adds a vision measurement to the Kalman Filter. More...
 
Pose2d Update (const Rotation2d &gyroAngle, const WheelPositions &wheelPositions)
 Updates the pose estimator with wheel encoder and gyro information. More...
 
Pose2d UpdateWithTime (units::second_t currentTime, const Rotation2d &gyroAngle, const WheelPositions &wheelPositions)
 Updates the pose estimator with wheel encoder and gyro information. More...
 

Detailed Description

This class wraps Mecanum Drive Odometry to fuse latency-compensated vision measurements with mecanum drive encoder velocity measurements.

It will correct for noisy measurements and encoder drift. It is intended to be an easy drop-in for MecanumDriveOdometry.

Update() should be called every robot loop. If your loops are faster or slower than the default of 20 ms, then you should change the nominal delta time by specifying it in the constructor.

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

Constructor & Destructor Documentation

◆ MecanumDrivePoseEstimator() [1/2]

frc::MecanumDrivePoseEstimator::MecanumDrivePoseEstimator ( MecanumDriveKinematics kinematics,
const Rotation2d gyroAngle,
const MecanumDriveWheelPositions wheelPositions,
const Pose2d initialPose 
)

Constructs a MecanumDrivePoseEstimator 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.45 meters for x, 0.45 meters for y, and 0.45 radians for heading.

Parameters
kinematicsA correctly-configured kinematics object for your drivetrain.
gyroAngleThe current gyro angle.
wheelPositionsThe distance measured by each wheel.
initialPoseThe starting pose estimate.

◆ MecanumDrivePoseEstimator() [2/2]

frc::MecanumDrivePoseEstimator::MecanumDrivePoseEstimator ( MecanumDriveKinematics kinematics,
const Rotation2d gyroAngle,
const MecanumDriveWheelPositions wheelPositions,
const Pose2d initialPose,
const wpi::array< double, 3 > &  stateStdDevs,
const wpi::array< double, 3 > &  visionMeasurementStdDevs 
)

Constructs a MecanumDrivePoseEstimator.

Parameters
kinematicsA correctly-configured kinematics object for your drivetrain.
gyroAngleThe current gyro angle.
wheelPositionsThe distance measured by each wheel.
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: