![]() |
WPILibC++ 2023.4.3
|
This class wraps Swerve Drive Odometry to fuse latency-compensated vision measurements with swerve drive encoder distance measurements. More...
#include <frc/estimator/SwerveDrivePoseEstimator.h>
Public Member Functions | |
SwerveDrivePoseEstimator (SwerveDriveKinematics< NumModules > &kinematics, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose) | |
Constructs a SwerveDrivePoseEstimator with default standard deviations for the model and vision measurements. More... | |
SwerveDrivePoseEstimator (SwerveDriveKinematics< NumModules > &kinematics, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose, const wpi::array< double, 3 > &stateStdDevs, const wpi::array< double, 3 > &visionMeasurementStdDevs) | |
Constructs a SwerveDrivePoseEstimator. More... | |
void | ResetPosition (const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &pose) |
Resets the robot's position on the field. More... | |
Pose2d | GetEstimatedPosition () const |
Gets the estimated robot pose. More... | |
void | SetVisionMeasurementStdDevs (const wpi::array< double, 3 > &visionMeasurementStdDevs) |
Sets the pose estimator's trust in vision measurements. 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 wpi::array< SwerveModulePosition, NumModules > &modulePositions) |
Updates the pose estimator with wheel encoder and gyro information. More... | |
Pose2d | UpdateWithTime (units::second_t currentTime, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions) |
Updates the pose estimator with wheel encoder and gyro information. More... | |
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.
|
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.
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. |
|
inline |
Constructs a SwerveDrivePoseEstimator.
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. |
|
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.
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 FPGA startup (i.e., the epoch of this timestamp is the same epoch as frc::Timer::GetFPGATimestamp().) This means that you should use frc::Timer::GetFPGATimestamp() as your time source or sync the epochs. |
|
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.
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 FPGA startup (i.e., the epoch of this timestamp is the same epoch as frc::Timer::GetFPGATimestamp(). This means that you should use frc::Timer::GetFPGATimestamp() 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. |
|
inline |
Gets the estimated robot 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.
gyroAngle | The angle reported by the gyroscope. |
modulePositions | The current distance and rotation measurements of the swerve modules. |
pose | The position on the field that your robot is at. |
|
inline |
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.
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 |
Updates the pose estimator with wheel encoder and gyro information.
This should be called every loop.
gyroAngle | The current gyro angle. |
modulePositions | The current distance and rotation measurements of the swerve modules. |
|
inline |
Updates the pose estimator with wheel encoder and gyro information.
This should be called every loop.
currentTime | Time at which this method was called, in seconds. |
gyroAngle | The current gyro angle. |
modulePositions | The current distance traveled and rotations of the swerve modules. |