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);
91 for (
size_t i = 0; i < 3; ++i) {
92 r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i];
97 for (
size_t row = 0; row < 3; ++row) {
98 if (m_q[row] == 0.0) {
99 m_vision_K.diagonal()[row] = 0.0;
101 m_vision_K.diagonal()[row] =
102 m_q[row] / (m_q[row] + std::sqrt(m_q[row] * r[row]));
118 const WheelPositions& wheelPositions,
const Pose2d& pose) {
120 m_odometry.ResetPosition(gyroAngle, wheelPositions, pose);
121 m_odometryPoseBuffer.Clear();
122 m_visionUpdates.clear();
123 m_poseEstimate = m_odometry.GetPose();
132 m_odometry.ResetPose(pose);
133 m_odometryPoseBuffer.Clear();
134 m_visionUpdates.clear();
135 m_poseEstimate = m_odometry.GetPose();
143#if defined(__GNUC__) && !defined(__clang__)
144#pragma GCC diagnostic push
145#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
148 m_odometry.ResetTranslation(translation);
150 const std::optional<std::pair<units::second_t, VisionUpdate>>
152 m_visionUpdates.empty() ? std::nullopt
153 : std::optional{*m_visionUpdates.crbegin()};
154 m_odometryPoseBuffer.Clear();
155 m_visionUpdates.clear();
157 if (latestVisionUpdate) {
159 const VisionUpdate visionUpdate{
160 Pose2d{translation, latestVisionUpdate->second.visionPose.Rotation()},
162 latestVisionUpdate->second.odometryPose.Rotation()}};
163 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
164 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
166 m_poseEstimate = m_odometry.GetPose();
169#if defined(__GNUC__) && !defined(__clang__)
170#pragma GCC diagnostic pop
178#if defined(__GNUC__) && !defined(__clang__)
179#pragma GCC diagnostic push
180#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
183 m_odometry.ResetRotation(rotation);
185 const std::optional<std::pair<units::second_t, VisionUpdate>>
187 m_visionUpdates.empty() ? std::nullopt
188 : std::optional{*m_visionUpdates.crbegin()};
189 m_odometryPoseBuffer.Clear();
190 m_visionUpdates.clear();
192 if (latestVisionUpdate) {
194 const VisionUpdate visionUpdate{
195 Pose2d{latestVisionUpdate->second.visionPose.Translation(), rotation},
196 Pose2d{latestVisionUpdate->second.odometryPose.Translation(),
198 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
199 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
201 m_poseEstimate = m_odometry.GetPose();
204#if defined(__GNUC__) && !defined(__clang__)
205#pragma GCC diagnostic pop
222 std::optional<Pose2d>
SampleAt(units::second_t timestamp)
const {
224 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
231 units::second_t oldestOdometryTimestamp =
232 m_odometryPoseBuffer.GetInternalBuffer().front().first;
233 units::second_t newestOdometryTimestamp =
234 m_odometryPoseBuffer.GetInternalBuffer().back().first;
236 std::clamp(timestamp, oldestOdometryTimestamp, newestOdometryTimestamp);
240 if (m_visionUpdates.empty() || timestamp < m_visionUpdates.begin()->first) {
241 return m_odometryPoseBuffer.Sample(timestamp);
249 auto floorIter = m_visionUpdates.upper_bound(timestamp);
251 auto visionUpdate = floorIter->second;
254 auto odometryEstimate = m_odometryPoseBuffer.Sample(timestamp);
258 if (odometryEstimate) {
259 return visionUpdate.Compensate(*odometryEstimate);
285 units::second_t timestamp) {
288 if (m_odometryPoseBuffer.GetInternalBuffer().empty() ||
289 m_odometryPoseBuffer.GetInternalBuffer().front().first -
296 CleanUpVisionUpdates();
300 auto odometrySample = m_odometryPoseBuffer.Sample(timestamp);
302 if (!odometrySample) {
308 auto visionSample = SampleAt(timestamp);
316 auto transform = visionRobotPose - visionSample.value();
321 Eigen::Vector3d k_times_transform =
322 m_vision_K * Eigen::Vector3d{transform.X().value(),
323 transform.Y().value(),
324 transform.Rotation().Radians().value()};
328 units::meter_t{k_times_transform(0)},
329 units::meter_t{k_times_transform(1)},
330 Rotation2d{units::radian_t{k_times_transform(2)}}};
333 VisionUpdate visionUpdate{*visionSample + scaledTransform, *odometrySample};
334 m_visionUpdates[timestamp] = visionUpdate;
337 auto firstAfter = m_visionUpdates.upper_bound(timestamp);
338 m_visionUpdates.erase(firstAfter, m_visionUpdates.end());
342 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
374 const Pose2d& visionRobotPose, units::second_t timestamp,
376 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
377 AddVisionMeasurement(visionRobotPose, timestamp);
390 const WheelPositions& wheelPositions) {
407 const WheelPositions& wheelPositions) {
408 auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions);
410 m_odometryPoseBuffer.AddSample(currentTime, odometryEstimate);
412 if (m_visionUpdates.empty()) {
413 m_poseEstimate = odometryEstimate;
415 auto visionUpdate = m_visionUpdates.rbegin()->second;
416 m_poseEstimate = visionUpdate.Compensate(odometryEstimate);
419 return GetEstimatedPosition();
426 void CleanUpVisionUpdates() {
428 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
433 units::second_t oldestOdometryTimestamp =
434 m_odometryPoseBuffer.GetInternalBuffer().front().first;
437 if (m_visionUpdates.empty() ||
438 oldestOdometryTimestamp < m_visionUpdates.begin()->first) {
447 auto newestNeededVisionUpdate =
448 m_visionUpdates.upper_bound(oldestOdometryTimestamp);
449 --newestNeededVisionUpdate;
452 m_visionUpdates.erase(m_visionUpdates.begin(), newestNeededVisionUpdate);
455 struct VisionUpdate {
470 Pose2d Compensate(
const Pose2d& pose)
const {
471 auto delta = pose - odometryPose;
472 return visionPose + delta;
476 static constexpr units::second_t kBufferDuration = 1.5_s;
478 Odometry<WheelSpeeds, WheelPositions>& m_odometry;
484 Eigen::DiagonalMatrix<double, 3> m_vision_K =
485 Eigen::DiagonalMatrix<double, 3>::Zero();
488 TimeInterpolatableBuffer<Pose2d> m_odometryPoseBuffer{kBufferDuration};
494 std::map<units::second_t, VisionUpdate> m_visionUpdates;
496 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:182
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:389
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:222
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:373
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:284
void ResetPose(const Pose2d &pose)
Resets the robot's pose.
Definition PoseEstimator.h:131
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:405
void ResetPosition(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition PoseEstimator.h:117
Pose2d GetEstimatedPosition() const
Gets the estimated robot pose.
Definition PoseEstimator.h:213
void ResetTranslation(const Translation2d &translation)
Resets the robot's translation.
Definition PoseEstimator.h:147
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