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);
96 for (
size_t i = 0; i < 4; ++i) {
97 r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i];
102 for (
size_t row = 0; row < 4; ++row) {
103 if (m_q[row] == 0.0) {
104 m_visionK(row, row) = 0.0;
106 m_visionK(row, row) =
107 m_q[row] / (m_q[row] + std::sqrt(m_q[row] * r[row]));
110 double angle_gain = m_visionK(3, 3);
111 m_visionK(4, 4) = angle_gain;
112 m_visionK(5, 5) = angle_gain;
126 const WheelPositions& wheelPositions,
const Pose3d& pose) {
128 m_odometry.ResetPosition(gyroAngle, wheelPositions, pose);
129 m_odometryPoseBuffer.Clear();
130 m_visionUpdates.clear();
131 m_poseEstimate = m_odometry.GetPose();
140 m_odometry.ResetPose(pose);
141 m_odometryPoseBuffer.Clear();
142 m_visionUpdates.clear();
143 m_poseEstimate = m_odometry.GetPose();
151#if defined(__GNUC__) && !defined(__clang__)
152#pragma GCC diagnostic push
153#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
156 m_odometry.ResetTranslation(translation);
158 const std::optional<std::pair<units::second_t, VisionUpdate>>
160 m_visionUpdates.empty() ? std::nullopt
161 : std::optional{*m_visionUpdates.crbegin()};
162 m_odometryPoseBuffer.Clear();
163 m_visionUpdates.clear();
165 if (latestVisionUpdate) {
167 const VisionUpdate visionUpdate{
168 Pose3d{translation, latestVisionUpdate->second.visionPose.Rotation()},
170 latestVisionUpdate->second.odometryPose.Rotation()}};
171 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
172 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
174 m_poseEstimate = m_odometry.GetPose();
177#if defined(__GNUC__) && !defined(__clang__)
178#pragma GCC diagnostic pop
186#if defined(__GNUC__) && !defined(__clang__)
187#pragma GCC diagnostic push
188#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
191 m_odometry.ResetRotation(rotation);
193 const std::optional<std::pair<units::second_t, VisionUpdate>>
195 m_visionUpdates.empty() ? std::nullopt
196 : std::optional{*m_visionUpdates.crbegin()};
197 m_odometryPoseBuffer.Clear();
198 m_visionUpdates.clear();
200 if (latestVisionUpdate) {
202 const VisionUpdate visionUpdate{
203 Pose3d{latestVisionUpdate->second.visionPose.Translation(), rotation},
204 Pose3d{latestVisionUpdate->second.odometryPose.Translation(),
206 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
207 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
209 m_poseEstimate = m_odometry.GetPose();
212#if defined(__GNUC__) && !defined(__clang__)
213#pragma GCC diagnostic pop
230 std::optional<Pose3d>
SampleAt(units::second_t timestamp)
const {
232 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
239 units::second_t oldestOdometryTimestamp =
240 m_odometryPoseBuffer.GetInternalBuffer().front().first;
241 units::second_t newestOdometryTimestamp =
242 m_odometryPoseBuffer.GetInternalBuffer().back().first;
244 std::clamp(timestamp, oldestOdometryTimestamp, newestOdometryTimestamp);
248 if (m_visionUpdates.empty() || timestamp < m_visionUpdates.begin()->first) {
249 return m_odometryPoseBuffer.Sample(timestamp);
257 auto floorIter = m_visionUpdates.upper_bound(timestamp);
259 auto visionUpdate = floorIter->second;
262 auto odometryEstimate = m_odometryPoseBuffer.Sample(timestamp);
266 if (odometryEstimate) {
267 return visionUpdate.Compensate(*odometryEstimate);
293 units::second_t timestamp) {
296 if (m_odometryPoseBuffer.GetInternalBuffer().empty() ||
297 m_odometryPoseBuffer.GetInternalBuffer().front().first -
304 CleanUpVisionUpdates();
308 auto odometrySample = m_odometryPoseBuffer.Sample(timestamp);
310 if (!odometrySample) {
316 auto visionSample = SampleAt(timestamp);
324 auto transform = visionRobotPose - visionSample.value();
331 transform.Y().value(),
332 transform.Z().value(),
333 transform.Rotation().X().value(),
334 transform.Rotation().Y().value(),
335 transform.Rotation().Z().value()};
339 units::meter_t{k_times_transform(0)},
340 units::meter_t{k_times_transform(1)},
341 units::meter_t{k_times_transform(2)},
342 Rotation3d{units::radian_t{k_times_transform(3)},
343 units::radian_t{k_times_transform(4)},
344 units::radian_t{k_times_transform(5)}}};
347 VisionUpdate visionUpdate{*visionSample + scaledTransform, *odometrySample};
348 m_visionUpdates[timestamp] = visionUpdate;
351 auto firstAfter = m_visionUpdates.upper_bound(timestamp);
352 m_visionUpdates.erase(firstAfter, m_visionUpdates.end());
356 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
388 const Pose3d& visionRobotPose, units::second_t timestamp,
390 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
391 AddVisionMeasurement(visionRobotPose, timestamp);
404 const WheelPositions& wheelPositions) {
421 const WheelPositions& wheelPositions) {
422 auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions);
424 m_odometryPoseBuffer.AddSample(currentTime, odometryEstimate);
426 if (m_visionUpdates.empty()) {
427 m_poseEstimate = odometryEstimate;
429 auto visionUpdate = m_visionUpdates.rbegin()->second;
430 m_poseEstimate = visionUpdate.Compensate(odometryEstimate);
433 return GetEstimatedPosition();
440 void CleanUpVisionUpdates() {
442 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
447 units::second_t oldestOdometryTimestamp =
448 m_odometryPoseBuffer.GetInternalBuffer().front().first;
451 if (m_visionUpdates.empty() ||
452 oldestOdometryTimestamp < m_visionUpdates.begin()->first) {
461 auto newestNeededVisionUpdate =
462 m_visionUpdates.upper_bound(oldestOdometryTimestamp);
463 --newestNeededVisionUpdate;
466 m_visionUpdates.erase(m_visionUpdates.begin(), newestNeededVisionUpdate);
469 struct VisionUpdate {
484 Pose3d Compensate(
const Pose3d& pose)
const {
485 auto delta = pose - odometryPose;
486 return visionPose + delta;
490 static constexpr units::second_t kBufferDuration = 1.5_s;
492 Odometry3d<WheelSpeeds, WheelPositions>& m_odometry;
497 TimeInterpolatableBuffer<Pose3d> m_odometryPoseBuffer{kBufferDuration};
503 std::map<units::second_t, VisionUpdate> m_visionUpdates;
505 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:190
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:419
void ResetTranslation(const Translation3d &translation)
Resets the robot's translation.
Definition PoseEstimator3d.h:155
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:230
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:292
void ResetPosition(const Rotation3d &gyroAngle, const WheelPositions &wheelPositions, const Pose3d &pose)
Resets the robot's position on the field.
Definition PoseEstimator3d.h:125
Pose3d Update(const Rotation3d &gyroAngle, const WheelPositions &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition PoseEstimator3d.h:403
void ResetPose(const Pose3d &pose)
Resets the robot's pose.
Definition PoseEstimator3d.h:139
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:387
Pose3d GetEstimatedPosition() const
Gets the estimated robot pose.
Definition PoseEstimator3d.h:221
A rotation in a 3D coordinate frame represented by a quaternion.
Definition Rotation3d.h:29
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::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
Eigen::Vector< double, Size > Vectord
Definition EigenCore.h:12
@ kEstimator_PoseEstimator3d
constexpr empty_array_t empty_array
Definition array.h:16