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{};
174 std::array<double, 3> m_r{};
176 struct VisionMatrices;
177 std::unique_ptr<VisionMatrices> m_matrices;
180 TimeInterpolatableBuffer<Pose2d> m_odometryPoseBuffer{kBufferDuration};
186 std::map<units::second_t, VisionUpdate> m_visionUpdates;
188 Pose2d m_poseEstimate;
193 void CleanUpVisionUpdates();
198 void UpdateVisionMatrices();
220 {0.1, 0.1, 0.1}, {0.9, 0.9, 0.9}}
242 std::array<double, 3>
const &stateStdDevs, std::array<double, 3>
const &visionMeasurementStdDevs);
256 for (
size_t i = 0; i < m_q.size(); ++i) {
257 m_q[i] = stateStdDevs[i] * stateStdDevs[i];
259 UpdateVisionMatrices();
274 for (
size_t i = 0; i < m_r.size(); ++i) {
275 m_r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i];
277 UpdateVisionMatrices();
292 m_odometry.ResetPosition(gyroAngle, std::move(wheelPositions), pose);
293 m_odometryPoseBuffer.Clear();
294 m_visionUpdates.clear();
295 m_poseEstimate = m_odometry.Pose();
305 m_odometry.ResetPose(pose);
306 m_odometryPoseBuffer.Clear();
307 m_visionUpdates.clear();
308 m_poseEstimate = m_odometry.Pose();
318 m_odometry.ResetTranslation(translation);
320 std::optional<std::pair<units::second_t, VisionUpdate>> latestVisionUpdate =
321 m_visionUpdates.empty() ? std::nullopt : std::optional{*m_visionUpdates.crbegin()};
322 m_odometryPoseBuffer.Clear();
323 m_visionUpdates.clear();
325 if (latestVisionUpdate) {
326 VisionUpdate
const visionUpdate{
327 Pose2d{translation, latestVisionUpdate->second.visionPose.Rotation()},
328 Pose2d{translation, latestVisionUpdate->second.odometryPose.Rotation()}
330 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
331 m_poseEstimate = visionUpdate.Compensate(m_odometry.Pose());
333 m_poseEstimate = m_odometry.Pose();
344 m_odometry.ResetRotation(rotation);
346 std::optional<std::pair<units::second_t, VisionUpdate>> latestVisionUpdate =
347 m_visionUpdates.empty() ? std::nullopt : std::optional{*m_visionUpdates.crbegin()};
348 m_odometryPoseBuffer.Clear();
349 m_visionUpdates.clear();
351 if (latestVisionUpdate) {
352 VisionUpdate
const visionUpdate{
353 Pose2d{latestVisionUpdate->second.visionPose.Translation(), rotation},
354 Pose2d{latestVisionUpdate->second.odometryPose.Translation(), rotation}
356 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
357 m_poseEstimate = visionUpdate.Compensate(m_odometry.Pose());
359 m_poseEstimate = m_odometry.Pose();
370 return m_poseEstimate;
380 std::optional<Pose2d>
SampleAt(units::second_t timestamp)
const;
433 std::array<double, 3>
const &visionMeasurementStdDevs)
435 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
436 AddVisionMeasurement(visionRobotPose, timestamp);
465 auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions);
467 m_odometryPoseBuffer.AddSample(currentTime, odometryEstimate);
469 if (m_visionUpdates.empty()) {
470 m_poseEstimate = std::move(odometryEstimate);
472 auto const visionUpdate = m_visionUpdates.rbegin()->second;
473 m_poseEstimate = visionUpdate.Compensate(odometryEstimate);
476 return GetEstimatedPosition();
Class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states ...
Definition SwerveDriveKinematics.hpp:41
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:463
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:290
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:368
void ResetTranslation(Translation2d const &translation)
Resets the robot's translation.
Definition SwerveDrivePoseEstimator.hpp:316
std::vector< SwerveModuleState > WheelSpeeds
Definition SwerveDrivePoseEstimator.hpp:144
void ResetPose(Pose2d const &pose)
Resets the robot's pose.
Definition SwerveDrivePoseEstimator.hpp:303
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:217
std::optional< Pose2d > SampleAt(units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
void SetStateStdDevs(std::array< double, 3 > const &stateStdDevs)
Sets the pose estimator's trust in robot odometry.
Definition SwerveDrivePoseEstimator.hpp:254
void ResetRotation(Rotation2d const &rotation)
Resets the robot's rotation.
Definition SwerveDrivePoseEstimator.hpp:342
void SetVisionMeasurementStdDevs(std::array< double, 3 > const &visionMeasurementStdDevs)
Sets the pose estimator's trust in vision measurements.
Definition SwerveDrivePoseEstimator.hpp:272
Pose2d Update(Rotation2d const &gyroAngle, WheelPositions const &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition SwerveDrivePoseEstimator.hpp:448
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:432
units::second_t GetCurrentTime()
Get the current timestamp.
Definition Utils.hpp:29
Definition motor_constants.h:14