39 Rotation2d m_previousAngle;
40 Rotation2d m_gyroOffset;
52 m_kinematics{kinematics},
53 m_pose{
std::move(initialPose)},
54 m_previousWheelPositions{
std::move(modulePositions)},
55 m_previousAngle{m_pose.Rotation()},
56 m_gyroOffset{m_pose.Rotation() - gyroAngle}
72 m_previousAngle = m_pose.Rotation();
73 m_gyroOffset = m_pose.Rotation() - gyroAngle;
74 m_previousWheelPositions = std::move(wheelPositions);
84 m_gyroOffset = m_gyroOffset + (pose.Rotation() - m_pose.Rotation());
86 m_previousAngle = pose.Rotation();
96 m_pose = Pose2d{translation, m_pose.Rotation()};
106 m_gyroOffset = m_gyroOffset + (rotation - m_pose.Rotation());
107 m_pose = Pose2d{m_pose.Translation(), rotation};
108 m_previousAngle = rotation;
116 Pose2d
const &
Pose()
const {
return m_pose; }
148 struct VisionUpdate {
163 Pose2d Compensate(
const Pose2d& pose)
const
165 auto const delta = pose - odometryPose;
166 return visionPose + delta;
170 static constexpr units::second_t kBufferDuration = 1.5_s;
173 std::array<double, 3> m_q{};
175 struct VisionMatrices;
176 std::unique_ptr<VisionMatrices> m_matrices;
185 std::map<units::second_t, VisionUpdate> m_visionUpdates;
187 Pose2d m_poseEstimate;
192 void CleanUpVisionUpdates();
214 {0.1, 0.1, 0.1}, {0.9, 0.9, 0.9}}
236 std::array<double, 3>
const &stateStdDevs, std::array<double, 3>
const &visionMeasurementStdDevs);
264 m_odometry.ResetPosition(gyroAngle, std::move(wheelPositions), pose);
265 m_odometryPoseBuffer.Clear();
266 m_visionUpdates.clear();
267 m_poseEstimate = m_odometry.Pose();
277 m_odometry.ResetPose(pose);
278 m_odometryPoseBuffer.Clear();
279 m_visionUpdates.clear();
280 m_poseEstimate = m_odometry.Pose();
290 m_odometry.ResetTranslation(translation);
291 m_odometryPoseBuffer.Clear();
292 m_visionUpdates.clear();
293 m_poseEstimate = m_odometry.Pose();
303 m_odometry.ResetRotation(rotation);
304 m_odometryPoseBuffer.Clear();
305 m_visionUpdates.clear();
306 m_poseEstimate = m_odometry.Pose();
316 return m_poseEstimate;
326 std::optional<Pose2d>
SampleAt(units::second_t timestamp)
const;
379 std::array<double, 3>
const &visionMeasurementStdDevs)
381 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
382 AddVisionMeasurement(visionRobotPose, timestamp);
411 auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions);
413 m_odometryPoseBuffer.AddSample(currentTime, odometryEstimate);
415 if (m_visionUpdates.empty()) {
416 m_poseEstimate = std::move(odometryEstimate);
418 auto const visionUpdate = m_visionUpdates.rbegin()->second;
419 m_poseEstimate = visionUpdate.Compensate(odometryEstimate);
422 return GetEstimatedPosition();
The TimeInterpolatableBuffer provides an easy way to estimate past measurements.
Definition TimeInterpolatableBuffer.hpp:31
Class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states ...
Definition SwerveDriveKinematics.hpp:42
Class for swerve drive odometry.
Definition SwerveDrivePoseEstimator.hpp:29
Pose2d const & Pose() const
Returns the position of the robot on the field.
Definition SwerveDrivePoseEstimator.hpp:116
void ResetPosition(Rotation2d const &gyroAngle, WheelPositions wheelPositions, Pose2d const &pose)
Resets the robot's position on the field.
Definition SwerveDrivePoseEstimator.hpp:69
std::vector< SwerveModulePosition > WheelPositions
Definition SwerveDrivePoseEstimator.hpp:32
void ResetRotation(Rotation2d const &rotation)
Resets the rotation of the pose.
Definition SwerveDrivePoseEstimator.hpp:104
Pose2d const & Update(Rotation2d const &gyroAngle, WheelPositions wheelPositions)
Updates the robot's position on the field using forward kinematics and integration of the pose over t...
std::vector< SwerveModuleState > WheelSpeeds
Definition SwerveDrivePoseEstimator.hpp:31
void ResetTranslation(Translation2d const &translation)
Resets the translation of the pose.
Definition SwerveDrivePoseEstimator.hpp:94
SwerveDriveOdometry(SwerveDriveKinematics const &kinematics, Rotation2d const &gyroAngle, WheelPositions modulePositions, Pose2d initialPose=Pose2d{})
Constructs a SwerveDriveOdometry object.
Definition SwerveDrivePoseEstimator.hpp:51
void ResetPose(Pose2d const &pose)
Resets the pose.
Definition SwerveDrivePoseEstimator.hpp:82
This class wraps Swerve Drive Odometry to fuse latency-compensated vision measurements with swerve dr...
Definition SwerveDrivePoseEstimator.hpp:142
Pose2d UpdateWithTime(units::second_t currentTime, Rotation2d const &gyroAngle, WheelPositions const &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition SwerveDrivePoseEstimator.hpp:409
std::vector< SwerveModulePosition > WheelPositions
Definition SwerveDrivePoseEstimator.hpp:145
~SwerveDrivePoseEstimator()
void ResetPosition(Rotation2d const &gyroAngle, WheelPositions wheelPositions, Pose2d const &pose)
Resets the robot's position on the field.
Definition SwerveDrivePoseEstimator.hpp:262
void AddVisionMeasurement(Pose2d const &visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
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.
Pose2d GetEstimatedPosition() const
Gets the estimated robot pose.
Definition SwerveDrivePoseEstimator.hpp:314
void ResetTranslation(Translation2d const &translation)
Resets the robot's translation.
Definition SwerveDrivePoseEstimator.hpp:288
std::vector< SwerveModuleState > WheelSpeeds
Definition SwerveDrivePoseEstimator.hpp:144
void ResetPose(Pose2d const &pose)
Resets the robot's pose.
Definition SwerveDrivePoseEstimator.hpp:275
SwerveDrivePoseEstimator(SwerveDriveKinematics const &kinematics, Rotation2d const &gyroAngle, WheelPositions modulePositions, Pose2d initialPose)
Constructs a SwerveDrivePoseEstimator with default standard deviations for the model and vision measu...
Definition SwerveDrivePoseEstimator.hpp:211
std::optional< Pose2d > SampleAt(units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
void ResetRotation(Rotation2d const &rotation)
Resets the robot's rotation.
Definition SwerveDrivePoseEstimator.hpp:301
void SetVisionMeasurementStdDevs(std::array< double, 3 > const &visionMeasurementStdDevs)
Sets the pose estimator's trust in vision measurements.
Pose2d Update(Rotation2d const &gyroAngle, WheelPositions const &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition SwerveDrivePoseEstimator.hpp:394
void AddVisionMeasurement(Pose2d const &visionRobotPose, units::second_t timestamp, std::array< double, 3 > const &visionMeasurementStdDevs)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivePoseEstimator.hpp:378
units::second_t GetCurrentTime()
Get the current timestamp.
Definition Utils.hpp:29
Definition StatusCodes.h:18