22#include "units/time.h"
43template <
typename WheelSpeeds,
typename WheelPositions>
67 : m_odometry(odometry) {
68 for (
size_t i = 0; i < 3; ++i) {
69 m_q[i] = stateStdDevs[i] * stateStdDevs[i];
72 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
90 for (
size_t i = 0; i < 3; ++i) {
91 r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i];
96 for (
size_t row = 0; row < 3; ++row) {
97 if (m_q[row] == 0.0) {
98 m_visionK(row, row) = 0.0;
100 m_visionK(row, row) =
101 m_q[row] / (m_q[row] + std::sqrt(m_q[row] * r[row]));
117 const WheelPositions& wheelPositions,
const Pose2d& pose) {
119 m_odometry.ResetPosition(gyroAngle, wheelPositions, pose);
120 m_odometryPoseBuffer.Clear();
121 m_visionUpdates.clear();
122 m_poseEstimate = m_odometry.GetPose();
131 m_odometry.ResetPose(pose);
132 m_odometryPoseBuffer.Clear();
133 m_visionUpdates.clear();
134 m_poseEstimate = m_odometry.GetPose();
142#if defined(__GNUC__) && !defined(__clang__)
143#pragma GCC diagnostic push
144#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
147 m_odometry.ResetTranslation(translation);
149 const std::optional<std::pair<units::second_t, VisionUpdate>>
151 m_visionUpdates.empty() ? std::nullopt
152 : std::optional{*m_visionUpdates.crbegin()};
153 m_odometryPoseBuffer.Clear();
154 m_visionUpdates.clear();
156 if (latestVisionUpdate) {
158 const VisionUpdate visionUpdate{
159 Pose2d{translation, latestVisionUpdate->second.visionPose.Rotation()},
161 latestVisionUpdate->second.odometryPose.Rotation()}};
162 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
163 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
165 m_poseEstimate = m_odometry.GetPose();
168#if defined(__GNUC__) && !defined(__clang__)
169#pragma GCC diagnostic pop
177#if defined(__GNUC__) && !defined(__clang__)
178#pragma GCC diagnostic push
179#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
182 m_odometry.ResetRotation(rotation);
184 const std::optional<std::pair<units::second_t, VisionUpdate>>
186 m_visionUpdates.empty() ? std::nullopt
187 : std::optional{*m_visionUpdates.crbegin()};
188 m_odometryPoseBuffer.Clear();
189 m_visionUpdates.clear();
191 if (latestVisionUpdate) {
193 const VisionUpdate visionUpdate{
194 Pose2d{latestVisionUpdate->second.visionPose.Translation(), rotation},
195 Pose2d{latestVisionUpdate->second.odometryPose.Translation(),
197 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
198 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
200 m_poseEstimate = m_odometry.GetPose();
203#if defined(__GNUC__) && !defined(__clang__)
204#pragma GCC diagnostic pop
221 std::optional<Pose2d>
SampleAt(units::second_t timestamp)
const {
223 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
230 units::second_t oldestOdometryTimestamp =
231 m_odometryPoseBuffer.GetInternalBuffer().front().first;
232 units::second_t newestOdometryTimestamp =
233 m_odometryPoseBuffer.GetInternalBuffer().back().first;
235 std::clamp(timestamp, oldestOdometryTimestamp, newestOdometryTimestamp);
239 if (m_visionUpdates.empty() || timestamp < m_visionUpdates.begin()->first) {
240 return m_odometryPoseBuffer.Sample(timestamp);
248 auto floorIter = m_visionUpdates.upper_bound(timestamp);
250 auto visionUpdate = floorIter->second;
253 auto odometryEstimate = m_odometryPoseBuffer.Sample(timestamp);
257 if (odometryEstimate) {
258 return visionUpdate.Compensate(*odometryEstimate);
284 units::second_t timestamp) {
287 if (m_odometryPoseBuffer.GetInternalBuffer().empty() ||
288 m_odometryPoseBuffer.GetInternalBuffer().front().first -
295 CleanUpVisionUpdates();
299 auto odometrySample = m_odometryPoseBuffer.Sample(timestamp);
301 if (!odometrySample) {
307 auto visionSample = SampleAt(timestamp);
315 auto transform = visionRobotPose - visionSample.value();
320 Eigen::Vector3d k_times_transform =
321 m_visionK * Eigen::Vector3d{transform.X().value(),
322 transform.Y().value(),
323 transform.Rotation().Radians().value()};
327 units::meter_t{k_times_transform(0)},
328 units::meter_t{k_times_transform(1)},
329 Rotation2d{units::radian_t{k_times_transform(2)}}};
332 VisionUpdate visionUpdate{*visionSample + scaledTransform, *odometrySample};
333 m_visionUpdates[timestamp] = visionUpdate;
336 auto firstAfter = m_visionUpdates.upper_bound(timestamp);
337 m_visionUpdates.erase(firstAfter, m_visionUpdates.end());
341 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
373 const Pose2d& visionRobotPose, units::second_t timestamp,
375 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
376 AddVisionMeasurement(visionRobotPose, timestamp);
389 const WheelPositions& wheelPositions) {
406 const WheelPositions& wheelPositions) {
407 auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions);
409 m_odometryPoseBuffer.AddSample(currentTime, odometryEstimate);
411 if (m_visionUpdates.empty()) {
412 m_poseEstimate = odometryEstimate;
414 auto visionUpdate = m_visionUpdates.rbegin()->second;
415 m_poseEstimate = visionUpdate.Compensate(odometryEstimate);
418 return GetEstimatedPosition();
425 void CleanUpVisionUpdates() {
427 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
432 units::second_t oldestOdometryTimestamp =
433 m_odometryPoseBuffer.GetInternalBuffer().front().first;
436 if (m_visionUpdates.empty() ||
437 oldestOdometryTimestamp < m_visionUpdates.begin()->first) {
446 auto newestNeededVisionUpdate =
447 m_visionUpdates.upper_bound(oldestOdometryTimestamp);
448 --newestNeededVisionUpdate;
451 m_visionUpdates.erase(m_visionUpdates.begin(), newestNeededVisionUpdate);
454 struct VisionUpdate {
469 Pose2d Compensate(
const Pose2d& pose)
const {
470 auto delta = pose - odometryPose;
471 return visionPose + delta;
475 static constexpr units::second_t kBufferDuration = 1.5_s;
477 Odometry<WheelSpeeds, WheelPositions>& m_odometry;
479 Eigen::Matrix3d m_visionK = Eigen::Matrix3d::Zero();
482 TimeInterpolatableBuffer<Pose2d> m_odometryPoseBuffer{kBufferDuration};
488 std::map<units::second_t, VisionUpdate> m_visionUpdates;
490 Pose2d m_poseEstimate;
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition Kinematics.h:25
Class for odometry.
Definition Odometry.h:30
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
This class wraps odometry to fuse latency-compensated vision measurements with encoder measurements.
Definition PoseEstimator.h:44
void ResetRotation(const Rotation2d &rotation)
Resets the robot's rotation.
Definition PoseEstimator.h:181
void SetVisionMeasurementStdDevs(const wpi::array< double, 3 > &visionMeasurementStdDevs)
Sets the pose estimator's trust in vision measurements.
Definition PoseEstimator.h:87
Pose2d Update(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition PoseEstimator.h:388
std::optional< Pose2d > SampleAt(units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
Definition PoseEstimator.h:221
void AddVisionMeasurement(const Pose2d &visionRobotPose, units::second_t timestamp, const wpi::array< double, 3 > &visionMeasurementStdDevs)
Adds a vision measurement to the Kalman Filter.
Definition PoseEstimator.h:372
PoseEstimator(Kinematics< WheelSpeeds, WheelPositions > &kinematics, Odometry< WheelSpeeds, WheelPositions > &odometry, const wpi::array< double, 3 > &stateStdDevs, const wpi::array< double, 3 > &visionMeasurementStdDevs)
Constructs a PoseEstimator.
Definition PoseEstimator.h:63
void AddVisionMeasurement(const Pose2d &visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition PoseEstimator.h:283
void ResetPose(const Pose2d &pose)
Resets the robot's pose.
Definition PoseEstimator.h:130
Pose2d UpdateWithTime(units::second_t currentTime, const Rotation2d &gyroAngle, const WheelPositions &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition PoseEstimator.h:404
void ResetPosition(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition PoseEstimator.h:116
Pose2d GetEstimatedPosition() const
Gets the estimated robot pose.
Definition PoseEstimator.h:212
void ResetTranslation(const Translation2d &translation)
Resets the robot's translation.
Definition PoseEstimator.h:146
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
Represents a translation in 2D space.
Definition Translation2d.h:30
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
static units::second_t GetTimestamp()
Definition MathShared.h:84
static void ReportUsage(MathUsageId id, int count)
Definition MathShared.h:80
@ kEstimator_PoseEstimator
constexpr empty_array_t empty_array
Definition array.h:16