WPILibC++ 2025.1.1
Loading...
Searching...
No Matches
frc::MecanumDrivePoseEstimator3d Class Reference

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

#include <frc/estimator/MecanumDrivePoseEstimator3d.h>

Inheritance diagram for frc::MecanumDrivePoseEstimator3d:
frc::PoseEstimator3d< MecanumDriveWheelSpeeds, MecanumDriveWheelPositions >

Public Member Functions

 MecanumDrivePoseEstimator3d (MecanumDriveKinematics &kinematics, const Rotation3d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose3d &initialPose)
 Constructs a MecanumDrivePoseEstimator3d with default standard deviations for the model and vision measurements.
 
 MecanumDrivePoseEstimator3d (MecanumDriveKinematics &kinematics, const Rotation3d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose3d &initialPose, const wpi::array< double, 4 > &stateStdDevs, const wpi::array< double, 4 > &visionMeasurementStdDevs)
 Constructs a MecanumDrivePoseEstimator3d.
 
- Public Member Functions inherited from frc::PoseEstimator3d< MecanumDriveWheelSpeeds, MecanumDriveWheelPositions >
 PoseEstimator3d (Kinematics< MecanumDriveWheelSpeeds, MecanumDriveWheelPositions > &kinematics, Odometry3d< MecanumDriveWheelSpeeds, MecanumDriveWheelPositions > &odometry, const wpi::array< double, 4 > &stateStdDevs, const wpi::array< double, 4 > &visionMeasurementStdDevs)
 Constructs a PoseEstimator3d.
 
void SetVisionMeasurementStdDevs (const wpi::array< double, 4 > &visionMeasurementStdDevs)
 Sets the pose estimator's trust in vision measurements.
 
void ResetPosition (const Rotation3d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose3d &pose)
 Resets the robot's position on the field.
 
void ResetPose (const Pose3d &pose)
 Resets the robot's pose.
 
void ResetTranslation (const Translation3d &translation)
 Resets the robot's translation.
 
void ResetRotation (const Rotation3d &rotation)
 Resets the robot's rotation.
 
Pose3d GetEstimatedPosition () const
 Gets the estimated robot pose.
 
std::optional< Pose3dSampleAt (units::second_t timestamp) const
 Return the pose at a given timestamp, if the buffer is not empty.
 
void AddVisionMeasurement (const Pose3d &visionRobotPose, units::second_t timestamp)
 Adds a vision measurement to the Kalman Filter.
 
void AddVisionMeasurement (const Pose3d &visionRobotPose, units::second_t timestamp, const wpi::array< double, 4 > &visionMeasurementStdDevs)
 Adds a vision measurement to the Kalman Filter.
 
Pose3d Update (const Rotation3d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions)
 Updates the pose estimator with wheel encoder and gyro information.
 
Pose3d UpdateWithTime (units::second_t currentTime, const Rotation3d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions)
 Updates the pose estimator with wheel encoder and gyro information.
 

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 MecanumDriveOdometry3d. It is also intended to be an easy replacement for PoseEstimator, only requiring the addition of a standard deviation for Z and appropriate conversions between 2D and 3D versions of geometry classes. (See Pose3d(Pose2d), Rotation3d(Rotation2d), Translation3d(Translation2d), and Pose3d.ToPose2d().)

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

◆ MecanumDrivePoseEstimator3d() [1/2]

frc::MecanumDrivePoseEstimator3d::MecanumDrivePoseEstimator3d ( MecanumDriveKinematics & kinematics,
const Rotation3d & gyroAngle,
const MecanumDriveWheelPositions & wheelPositions,
const Pose3d & initialPose )

Constructs a MecanumDrivePoseEstimator3d 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, 0.1 meters for z, and 0.1 radians for angle. The default standard deviations of the vision measurements are 0.45 meters for x, 0.45 meters for y, 0.45 meters for z, and 0.45 radians for angle.

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

◆ MecanumDrivePoseEstimator3d() [2/2]

frc::MecanumDrivePoseEstimator3d::MecanumDrivePoseEstimator3d ( MecanumDriveKinematics & kinematics,
const Rotation3d & gyroAngle,
const MecanumDriveWheelPositions & wheelPositions,
const Pose3d & initialPose,
const wpi::array< double, 4 > & stateStdDevs,
const wpi::array< double, 4 > & visionMeasurementStdDevs )

Constructs a MecanumDrivePoseEstimator3d.

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, z position in meters, and angle 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, z position in meters, and angle in radians). Increase these numbers to trust the vision pose measurement less.

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