This class wraps Swerve Drive Odometry to fuse latency-compensated vision measurements with swerve drive encoder distance measurements.
More...
#include <ctre/phoenix6/swerve/impl/SwerveDrivePoseEstimator.hpp>
|
| SwerveDrivePoseEstimator (SwerveDriveKinematics const &kinematics, Rotation2d const &gyroAngle, WheelPositions modulePositions, Pose2d initialPose) |
| Constructs a SwerveDrivePoseEstimator with default standard deviations for the model and vision measurements.
|
|
| SwerveDrivePoseEstimator (SwerveDriveKinematics const &kinematics, Rotation2d const &gyroAngle, WheelPositions modulePositions, Pose2d initialPose, std::array< double, 3 > const &stateStdDevs, std::array< double, 3 > const &visionMeasurementStdDevs) |
| Constructs a SwerveDrivePoseEstimator.
|
|
| ~SwerveDrivePoseEstimator () |
|
void | SetVisionMeasurementStdDevs (std::array< double, 3 > const &visionMeasurementStdDevs) |
| Sets the pose estimator's trust in vision measurements.
|
|
void | ResetPosition (Rotation2d const &gyroAngle, WheelPositions wheelPositions, Pose2d const &pose) |
| Resets the robot's position on the field.
|
|
void | ResetPose (Pose2d const &pose) |
| Resets the robot's pose.
|
|
void | ResetTranslation (Translation2d const &translation) |
| Resets the robot's translation.
|
|
void | ResetRotation (Rotation2d const &rotation) |
| Resets the robot's rotation.
|
|
Pose2d | GetEstimatedPosition () const |
| Gets the estimated robot pose.
|
|
std::optional< Pose2d > | SampleAt (units::second_t timestamp) const |
| Return the pose at a given timestamp, if the buffer is not empty.
|
|
void | AddVisionMeasurement (Pose2d const &visionRobotPose, units::second_t timestamp) |
| Adds a vision measurement to the Kalman Filter.
|
|
void | AddVisionMeasurement (Pose2d const &visionRobotPose, units::second_t timestamp, std::array< double, 3 > const &visionMeasurementStdDevs) |
| Adds a vision measurement to the Kalman Filter.
|
|
Pose2d | Update (Rotation2d const &gyroAngle, WheelPositions const &wheelPositions) |
| Updates the pose estimator with wheel encoder and gyro information.
|
|
Pose2d | UpdateWithTime (units::second_t currentTime, Rotation2d const &gyroAngle, WheelPositions const &wheelPositions) |
| Updates the pose estimator with wheel encoder and gyro information.
|
|
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.
◆ WheelPositions
◆ WheelSpeeds
◆ SwerveDrivePoseEstimator() [1/2]
ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::SwerveDrivePoseEstimator |
( |
SwerveDriveKinematics const & | kinematics, |
|
|
Rotation2d const & | gyroAngle, |
|
|
WheelPositions | modulePositions, |
|
|
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
-
kinematics | A correctly-configured kinematics object for your drivetrain. |
gyroAngle | The current gyro angle. |
modulePositions | The current distance and rotation measurements of the swerve modules. |
initialPose | The starting pose estimate. |
◆ SwerveDrivePoseEstimator() [2/2]
ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::SwerveDrivePoseEstimator |
( |
SwerveDriveKinematics const & | kinematics, |
|
|
Rotation2d const & | gyroAngle, |
|
|
WheelPositions | modulePositions, |
|
|
Pose2d | initialPose, |
|
|
std::array< double, 3 > const & | stateStdDevs, |
|
|
std::array< double, 3 > const & | visionMeasurementStdDevs ) |
Constructs a SwerveDrivePoseEstimator.
- Parameters
-
kinematics | A correctly-configured kinematics object for your drivetrain. |
gyroAngle | The current gyro angle. |
modulePositions | The current distance and rotation measurements of the swerve modules. |
initialPose | The starting pose estimate. |
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. |
◆ ~SwerveDrivePoseEstimator()
ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::~SwerveDrivePoseEstimator |
( |
| ) |
|
◆ AddVisionMeasurement() [1/2]
void ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::AddVisionMeasurement |
( |
Pose2d const & | visionRobotPose, |
|
|
units::second_t | timestamp ) |
Adds a vision measurement to the Kalman Filter.
This will correct the odometry pose estimate while still accounting for measurement noise.
This method can be called as infrequently as you want, as long as you are calling Update() every loop.
To promote stability of the pose estimate and make it robust to bad vision data, we recommend only adding vision measurements that are already within one meter or so of the current pose estimate.
- Parameters
-
visionRobotPose | The pose of the robot as measured by the vision camera. |
timestamp | The timestamp of the vision measurement in seconds. Note that if you don't use your own time source by calling UpdateWithTime(), then you must use a timestamp with an epoch since system startup (i.e., the epoch of this timestamp is the same epoch as utils::GetCurrentTime(). This means that you should use utils::GetCurrentTime() as your time source in this case. |
◆ AddVisionMeasurement() [2/2]
void ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::AddVisionMeasurement |
( |
Pose2d const & | visionRobotPose, |
|
|
units::second_t | timestamp, |
|
|
std::array< double, 3 > const & | visionMeasurementStdDevs ) |
|
inline |
Adds a vision measurement to the Kalman Filter.
This will correct the odometry pose estimate while still accounting for measurement noise.
This method can be called as infrequently as you want, as long as you are calling Update() every loop.
To promote stability of the pose estimate and make it robust to bad vision data, we recommend only adding vision measurements that are already within one meter or so of the current pose estimate.
Note that the vision measurement standard deviations passed into this method will continue to apply to future measurements until a subsequent call to SetVisionMeasurementStdDevs() or this method.
- Parameters
-
visionRobotPose | The pose of the robot as measured by the vision camera. |
timestamp | The timestamp of the vision measurement in seconds. Note that if you don't use your own time source by calling UpdateWithTime(), then you must use a timestamp with an epoch since system startup (i.e., the epoch of this timestamp is the same epoch as utils::GetCurrentTime(). This means that you should use utils::GetCurrentTime() as your time source in this case. |
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. |
◆ GetEstimatedPosition()
Pose2d ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::GetEstimatedPosition |
( |
| ) |
const |
|
inline |
Gets the estimated robot pose.
- Returns
- The estimated robot pose in meters.
◆ ResetPose()
void ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::ResetPose |
( |
Pose2d const & | pose | ) |
|
|
inline |
Resets the robot's pose.
- Parameters
-
pose | The pose to reset to. |
◆ ResetPosition()
void ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::ResetPosition |
( |
Rotation2d const & | gyroAngle, |
|
|
WheelPositions | wheelPositions, |
|
|
Pose2d const & | pose ) |
|
inline |
Resets the robot's position on the field.
The gyroscope angle does not need to be reset in the user's robot code. The library automatically takes care of offsetting the gyro angle.
- Parameters
-
gyroAngle | The current gyro angle. |
wheelPositions | The distances traveled by the encoders. |
pose | The estimated pose of the robot on the field. |
◆ ResetRotation()
void ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::ResetRotation |
( |
Rotation2d const & | rotation | ) |
|
|
inline |
Resets the robot's rotation.
- Parameters
-
rotation | The rotation to reset to. |
◆ ResetTranslation()
void ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::ResetTranslation |
( |
Translation2d const & | translation | ) |
|
|
inline |
Resets the robot's translation.
- Parameters
-
translation | The pose to translation to. |
◆ SampleAt()
std::optional< Pose2d > ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::SampleAt |
( |
units::second_t | timestamp | ) |
const |
Return the pose at a given timestamp, if the buffer is not empty.
- Parameters
-
timestamp | The pose's timestamp. |
- Returns
- The pose at the given timestamp (or std::nullopt if the buffer is empty).
◆ SetVisionMeasurementStdDevs()
void ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::SetVisionMeasurementStdDevs |
( |
std::array< double, 3 > const & | visionMeasurementStdDevs | ) |
|
Sets the pose estimator's trust in vision measurements.
This might be used to change trust in vision measurements after the autonomous period, or to change trust as distance to a vision target increases.
- Parameters
-
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. |
◆ Update()
Pose2d ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::Update |
( |
Rotation2d const & | gyroAngle, |
|
|
WheelPositions const & | wheelPositions ) |
|
inline |
Updates the pose estimator with wheel encoder and gyro information.
This should be called every loop.
- Parameters
-
gyroAngle | The current gyro angle. |
wheelPositions | The distances traveled by the encoders. |
- Returns
- The estimated pose of the robot in meters.
◆ UpdateWithTime()
Pose2d ctre::phoenix6::swerve::impl::SwerveDrivePoseEstimator::UpdateWithTime |
( |
units::second_t | currentTime, |
|
|
Rotation2d const & | gyroAngle, |
|
|
WheelPositions const & | wheelPositions ) |
|
inline |
Updates the pose estimator with wheel encoder and gyro information.
This should be called every loop.
- Parameters
-
currentTime | The time at which this method was called. |
gyroAngle | The current gyro angle. |
wheelPositions | The distances traveled by the encoders. |
- Returns
- The estimated pose of the robot in meters.
The documentation for this class was generated from the following file: