WPILibC++ 2024.3.2
frc::DifferentialDrivePoseEstimator Class Reference

This class wraps Differential Drive Odometry to fuse latency-compensated vision measurements with differential drive encoder measurements. More...

#include <frc/estimator/DifferentialDrivePoseEstimator.h>

Inheritance diagram for frc::DifferentialDrivePoseEstimator:
frc::PoseEstimator< DifferentialDriveWheelSpeeds, DifferentialDriveWheelPositions >

Public Member Functions

 DifferentialDrivePoseEstimator (DifferentialDriveKinematics &kinematics, const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose2d &initialPose)
 Constructs a DifferentialDrivePoseEstimator with default standard deviations for the model and vision measurements. More...
 
 DifferentialDrivePoseEstimator (DifferentialDriveKinematics &kinematics, const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose2d &initialPose, const wpi::array< double, 3 > &stateStdDevs, const wpi::array< double, 3 > &visionMeasurementStdDevs)
 Constructs a DifferentialDrivePoseEstimator. More...
 
void ResetPosition (const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose2d &pose)
 Resets the robot's position on the field. More...
 
Pose2d Update (const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance)
 Updates the pose estimator with wheel encoder and gyro information. More...
 
Pose2d UpdateWithTime (units::second_t currentTime, const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance)
 Updates the pose estimator with wheel encoder and gyro information. More...
 
- Public Member Functions inherited from frc::PoseEstimator< DifferentialDriveWheelSpeeds, DifferentialDriveWheelPositions >
 PoseEstimator (Kinematics< DifferentialDriveWheelSpeeds, WheelPositions > &kinematics, Odometry< DifferentialDriveWheelSpeeds, 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 Differential Drive Odometry to fuse latency-compensated vision measurements with differential drive encoder measurements.

It will correct for noisy vision measurements and encoder drift. It is intended to be an easy drop-in for DifferentialDriveOdometry. In fact, if you never call AddVisionMeasurement(), and only call Update(), this will behave exactly the same as DifferentialDriveOdometry.

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

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

Constructor & Destructor Documentation

◆ DifferentialDrivePoseEstimator() [1/2]

frc::DifferentialDrivePoseEstimator::DifferentialDrivePoseEstimator ( DifferentialDriveKinematics kinematics,
const Rotation2d gyroAngle,
units::meter_t  leftDistance,
units::meter_t  rightDistance,
const Pose2d initialPose 
)

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

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

Parameters
kinematicsA correctly-configured kinematics object for your drivetrain.
gyroAngleThe gyro angle of the robot.
leftDistanceThe distance traveled by the left encoder.
rightDistanceThe distance traveled by the right encoder.
initialPoseThe estimated initial pose.

◆ DifferentialDrivePoseEstimator() [2/2]

frc::DifferentialDrivePoseEstimator::DifferentialDrivePoseEstimator ( DifferentialDriveKinematics kinematics,
const Rotation2d gyroAngle,
units::meter_t  leftDistance,
units::meter_t  rightDistance,
const Pose2d initialPose,
const wpi::array< double, 3 > &  stateStdDevs,
const wpi::array< double, 3 > &  visionMeasurementStdDevs 
)

Constructs a DifferentialDrivePoseEstimator.

Parameters
kinematicsA correctly-configured kinematics object for your drivetrain.
gyroAngleThe gyro angle of the robot.
leftDistanceThe distance traveled by the left encoder.
rightDistanceThe distance traveled by the right encoder.
initialPoseThe estimated initial pose.
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.

Member Function Documentation

◆ ResetPosition()

void frc::DifferentialDrivePoseEstimator::ResetPosition ( const Rotation2d gyroAngle,
units::meter_t  leftDistance,
units::meter_t  rightDistance,
const Pose2d pose 
)
inline

Resets the robot's position on the field.

Parameters
gyroAngleThe current gyro angle.
leftDistanceThe distance traveled by the left encoder.
rightDistanceThe distance traveled by the right encoder.
poseThe estimated pose of the robot on the field.

◆ Update()

Pose2d frc::DifferentialDrivePoseEstimator::Update ( const Rotation2d gyroAngle,
units::meter_t  leftDistance,
units::meter_t  rightDistance 
)
inline

Updates the pose estimator with wheel encoder and gyro information.

This should be called every loop.

Parameters
gyroAngleThe current gyro angle.
leftDistanceThe distance traveled by the left encoder.
rightDistanceThe distance traveled by the right encoder.
Returns
The estimated pose of the robot.

◆ UpdateWithTime()

Pose2d frc::DifferentialDrivePoseEstimator::UpdateWithTime ( units::second_t  currentTime,
const Rotation2d gyroAngle,
units::meter_t  leftDistance,
units::meter_t  rightDistance 
)
inline

Updates the pose estimator with wheel encoder and gyro information.

This should be called every loop.

Parameters
currentTimeThe time at which this method was called.
gyroAngleThe current gyro angle.
leftDistanceThe distance traveled by the left encoder.
rightDistanceThe distance traveled by the right encoder.
Returns
The estimated pose of the robot.

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