24#include "units/time.h"
49template <
typename WheelSpeeds,
typename WheelPositions>
73 : m_odometry(odometry) {
74 for (
size_t i = 0; i < 4; ++i) {
75 m_q[i] = stateStdDevs[i] * stateStdDevs[i];
78 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
97 for (
size_t i = 0; i < 4; ++i) {
98 r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i];
103 for (
size_t row = 0; row < 4; ++row) {
104 if (m_q[row] == 0.0) {
105 m_vision_K.diagonal()[row] = 0.0;
107 m_vision_K.diagonal()[row] =
108 m_q[row] / (m_q[row] + std::sqrt(m_q[row] * r[row]));
111 double angle_gain = m_vision_K.diagonal()[3];
112 m_vision_K.diagonal()[4] = angle_gain;
113 m_vision_K.diagonal()[5] = angle_gain;
127 const WheelPositions& wheelPositions,
const Pose3d& pose) {
129 m_odometry.ResetPosition(gyroAngle, wheelPositions, pose);
130 m_odometryPoseBuffer.Clear();
131 m_visionUpdates.clear();
132 m_poseEstimate = m_odometry.GetPose();
141 m_odometry.ResetPose(pose);
142 m_odometryPoseBuffer.Clear();
143 m_visionUpdates.clear();
144 m_poseEstimate = m_odometry.GetPose();
152#if defined(__GNUC__) && !defined(__clang__)
153#pragma GCC diagnostic push
154#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
157 m_odometry.ResetTranslation(translation);
159 const std::optional<std::pair<units::second_t, VisionUpdate>>
161 m_visionUpdates.empty() ? std::nullopt
162 : std::optional{*m_visionUpdates.crbegin()};
163 m_odometryPoseBuffer.Clear();
164 m_visionUpdates.clear();
166 if (latestVisionUpdate) {
168 const VisionUpdate visionUpdate{
169 Pose3d{translation, latestVisionUpdate->second.visionPose.Rotation()},
171 latestVisionUpdate->second.odometryPose.Rotation()}};
172 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
173 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
175 m_poseEstimate = m_odometry.GetPose();
178#if defined(__GNUC__) && !defined(__clang__)
179#pragma GCC diagnostic pop
187#if defined(__GNUC__) && !defined(__clang__)
188#pragma GCC diagnostic push
189#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
192 m_odometry.ResetRotation(rotation);
194 const std::optional<std::pair<units::second_t, VisionUpdate>>
196 m_visionUpdates.empty() ? std::nullopt
197 : std::optional{*m_visionUpdates.crbegin()};
198 m_odometryPoseBuffer.Clear();
199 m_visionUpdates.clear();
201 if (latestVisionUpdate) {
203 const VisionUpdate visionUpdate{
204 Pose3d{latestVisionUpdate->second.visionPose.Translation(), rotation},
205 Pose3d{latestVisionUpdate->second.odometryPose.Translation(),
207 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
208 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
210 m_poseEstimate = m_odometry.GetPose();
213#if defined(__GNUC__) && !defined(__clang__)
214#pragma GCC diagnostic pop
231 std::optional<Pose3d>
SampleAt(units::second_t timestamp)
const {
233 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
240 units::second_t oldestOdometryTimestamp =
241 m_odometryPoseBuffer.GetInternalBuffer().front().first;
242 units::second_t newestOdometryTimestamp =
243 m_odometryPoseBuffer.GetInternalBuffer().back().first;
245 std::clamp(timestamp, oldestOdometryTimestamp, newestOdometryTimestamp);
249 if (m_visionUpdates.empty() || timestamp < m_visionUpdates.begin()->first) {
250 return m_odometryPoseBuffer.Sample(timestamp);
258 auto floorIter = m_visionUpdates.upper_bound(timestamp);
260 auto visionUpdate = floorIter->second;
263 auto odometryEstimate = m_odometryPoseBuffer.Sample(timestamp);
267 if (odometryEstimate) {
268 return visionUpdate.Compensate(*odometryEstimate);
294 units::second_t timestamp) {
297 if (m_odometryPoseBuffer.GetInternalBuffer().empty() ||
298 m_odometryPoseBuffer.GetInternalBuffer().front().first -
305 CleanUpVisionUpdates();
309 auto odometrySample = m_odometryPoseBuffer.Sample(timestamp);
311 if (!odometrySample) {
317 auto visionSample = SampleAt(timestamp);
325 auto transform = visionRobotPose - visionSample.value();
332 transform.Y().value(),
333 transform.Z().value(),
334 transform.Rotation().X().value(),
335 transform.Rotation().Y().value(),
336 transform.Rotation().Z().value()};
340 units::meter_t{k_times_transform(0)},
341 units::meter_t{k_times_transform(1)},
342 units::meter_t{k_times_transform(2)},
343 Rotation3d{units::radian_t{k_times_transform(3)},
344 units::radian_t{k_times_transform(4)},
345 units::radian_t{k_times_transform(5)}}};
348 VisionUpdate visionUpdate{*visionSample + scaledTransform, *odometrySample};
349 m_visionUpdates[timestamp] = visionUpdate;
352 auto firstAfter = m_visionUpdates.upper_bound(timestamp);
353 m_visionUpdates.erase(firstAfter, m_visionUpdates.end());
357 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
389 const Pose3d& visionRobotPose, units::second_t timestamp,
391 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
392 AddVisionMeasurement(visionRobotPose, timestamp);
405 const WheelPositions& wheelPositions) {
422 const WheelPositions& wheelPositions) {
423 auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions);
425 m_odometryPoseBuffer.AddSample(currentTime, odometryEstimate);
427 if (m_visionUpdates.empty()) {
428 m_poseEstimate = odometryEstimate;
430 auto visionUpdate = m_visionUpdates.rbegin()->second;
431 m_poseEstimate = visionUpdate.Compensate(odometryEstimate);
434 return GetEstimatedPosition();
441 void CleanUpVisionUpdates() {
443 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
448 units::second_t oldestOdometryTimestamp =
449 m_odometryPoseBuffer.GetInternalBuffer().front().first;
452 if (m_visionUpdates.empty() ||
453 oldestOdometryTimestamp < m_visionUpdates.begin()->first) {
462 auto newestNeededVisionUpdate =
463 m_visionUpdates.upper_bound(oldestOdometryTimestamp);
464 --newestNeededVisionUpdate;
467 m_visionUpdates.erase(m_visionUpdates.begin(), newestNeededVisionUpdate);
470 struct VisionUpdate {
485 Pose3d Compensate(
const Pose3d& pose)
const {
486 auto delta = pose - odometryPose;
487 return visionPose + delta;
491 static constexpr units::second_t kBufferDuration = 1.5_s;
493 Odometry3d<WheelSpeeds, WheelPositions>& m_odometry;
499 Eigen::DiagonalMatrix<double, 6> m_vision_K =
500 Eigen::DiagonalMatrix<double, 6>::Zero();
503 TimeInterpolatableBuffer<Pose3d> m_odometryPoseBuffer{kBufferDuration};
509 std::map<units::second_t, VisionUpdate> m_visionUpdates;
511 Pose3d 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 Odometry3d.h:33
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.h:31
This class wraps odometry to fuse latency-compensated vision measurements with encoder measurements.
Definition PoseEstimator3d.h:50
void ResetRotation(const Rotation3d &rotation)
Resets the robot's rotation.
Definition PoseEstimator3d.h:191
PoseEstimator3d(Kinematics< WheelSpeeds, WheelPositions > &kinematics, Odometry3d< WheelSpeeds, WheelPositions > &odometry, const wpi::array< double, 4 > &stateStdDevs, const wpi::array< double, 4 > &visionMeasurementStdDevs)
Constructs a PoseEstimator3d.
Definition PoseEstimator3d.h:69
Pose3d UpdateWithTime(units::second_t currentTime, const Rotation3d &gyroAngle, const WheelPositions &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition PoseEstimator3d.h:420
void ResetTranslation(const Translation3d &translation)
Resets the robot's translation.
Definition PoseEstimator3d.h:156
std::optional< Pose3d > SampleAt(units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
Definition PoseEstimator3d.h:231
void SetVisionMeasurementStdDevs(const wpi::array< double, 4 > &visionMeasurementStdDevs)
Sets the pose estimator's trust in vision measurements.
Definition PoseEstimator3d.h:93
void AddVisionMeasurement(const Pose3d &visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition PoseEstimator3d.h:293
void ResetPosition(const Rotation3d &gyroAngle, const WheelPositions &wheelPositions, const Pose3d &pose)
Resets the robot's position on the field.
Definition PoseEstimator3d.h:126
Pose3d Update(const Rotation3d &gyroAngle, const WheelPositions &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition PoseEstimator3d.h:404
void ResetPose(const Pose3d &pose)
Resets the robot's pose.
Definition PoseEstimator3d.h:140
void AddVisionMeasurement(const Pose3d &visionRobotPose, units::second_t timestamp, const wpi::array< double, 4 > &visionMeasurementStdDevs)
Adds a vision measurement to the Kalman Filter.
Definition PoseEstimator3d.h:388
Pose3d GetEstimatedPosition() const
Gets the estimated robot pose.
Definition PoseEstimator3d.h:222
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.h:72
Represents a translation in 3D space.
Definition Translation3d.h:31
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
Eigen::Vector< double, Size > Vectord
Definition EigenCore.h:12
@ kEstimator_PoseEstimator3d
constexpr empty_array_t empty_array
Definition array.h:16