WPILibC++ 2024.3.2
|
This class wraps Differential Drive Odometry to fuse latency-compensated vision measurements with differential drive encoder measurements. More...
#include <frc/estimator/DifferentialDrivePoseEstimator.h>
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... | |
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.
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.
kinematics | A correctly-configured kinematics object for your drivetrain. |
gyroAngle | The gyro angle of the robot. |
leftDistance | The distance traveled by the left encoder. |
rightDistance | The distance traveled by the right encoder. |
initialPose | The estimated initial pose. |
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.
kinematics | A correctly-configured kinematics object for your drivetrain. |
gyroAngle | The gyro angle of the robot. |
leftDistance | The distance traveled by the left encoder. |
rightDistance | The distance traveled by the right encoder. |
initialPose | The estimated initial pose. |
stateStdDevs | Standard 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. |
visionMeasurementStdDevs | Standard 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. |
|
inline |
Resets the robot's position on the field.
gyroAngle | The current gyro angle. |
leftDistance | The distance traveled by the left encoder. |
rightDistance | The distance traveled by the right encoder. |
pose | The estimated pose of the robot on the field. |
|
inline |
Updates the pose estimator with wheel encoder and gyro information.
This should be called every loop.
gyroAngle | The current gyro angle. |
leftDistance | The distance traveled by the left encoder. |
rightDistance | The distance traveled by the right encoder. |
|
inline |
Updates the pose estimator with wheel encoder and gyro information.
This should be called every loop.
currentTime | The time at which this method was called. |
gyroAngle | The current gyro angle. |
leftDistance | The distance traveled by the left encoder. |
rightDistance | The distance traveled by the right encoder. |