22#include "wpi/units/time.hpp"
45template <
typename WheelPositions,
typename WheelVelocities,
46 typename WheelAccelerations>
72 : m_odometry(odometry) {
73 for (
size_t i = 0; i < 3; ++i) {
74 m_q[i] = stateStdDevs[i] * stateStdDevs[i];
95 for (
size_t i = 0; i < 3; ++i) {
96 r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i];
101 for (
size_t row = 0; row < 3; ++row) {
102 if (m_q[row] == 0.0) {
103 m_vision_K.diagonal()[row] = 0.0;
105 m_vision_K.diagonal()[row] =
106 m_q[row] / (m_q[row] + std::sqrt(m_q[row] * r[row]));
122 const WheelPositions& wheelPositions,
const Pose2d& pose) {
124 m_odometry.ResetPosition(gyroAngle, wheelPositions, pose);
125 m_odometryPoseBuffer.Clear();
126 m_visionUpdates.clear();
127 m_poseEstimate = m_odometry.GetPose();
136 m_odometry.ResetPose(pose);
137 m_odometryPoseBuffer.Clear();
138 m_visionUpdates.clear();
139 m_poseEstimate = m_odometry.GetPose();
147#if defined(__GNUC__) && !defined(__clang__)
148#pragma GCC diagnostic push
149#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
152 m_odometry.ResetTranslation(translation);
154 const std::optional<std::pair<units::second_t, VisionUpdate>>
156 m_visionUpdates.empty() ? std::nullopt
157 : std::optional{*m_visionUpdates.crbegin()};
158 m_odometryPoseBuffer.Clear();
159 m_visionUpdates.clear();
161 if (latestVisionUpdate) {
163 const VisionUpdate visionUpdate{
164 Pose2d{translation, latestVisionUpdate->second.visionPose.Rotation()},
166 latestVisionUpdate->second.odometryPose.Rotation()}};
167 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
168 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
170 m_poseEstimate = m_odometry.GetPose();
173#if defined(__GNUC__) && !defined(__clang__)
174#pragma GCC diagnostic pop
182#if defined(__GNUC__) && !defined(__clang__)
183#pragma GCC diagnostic push
184#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
187 m_odometry.ResetRotation(rotation);
189 const std::optional<std::pair<units::second_t, VisionUpdate>>
191 m_visionUpdates.empty() ? std::nullopt
192 : std::optional{*m_visionUpdates.crbegin()};
193 m_odometryPoseBuffer.Clear();
194 m_visionUpdates.clear();
196 if (latestVisionUpdate) {
198 const VisionUpdate visionUpdate{
199 Pose2d{latestVisionUpdate->second.visionPose.Translation(), rotation},
200 Pose2d{latestVisionUpdate->second.odometryPose.Translation(),
202 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
203 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
205 m_poseEstimate = m_odometry.GetPose();
208#if defined(__GNUC__) && !defined(__clang__)
209#pragma GCC diagnostic pop
226 std::optional<Pose2d>
SampleAt(wpi::units::second_t timestamp)
const {
228 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
235 wpi::units::second_t oldestOdometryTimestamp =
236 m_odometryPoseBuffer.GetInternalBuffer().front().first;
237 wpi::units::second_t newestOdometryTimestamp =
238 m_odometryPoseBuffer.GetInternalBuffer().back().first;
240 std::clamp(timestamp, oldestOdometryTimestamp, newestOdometryTimestamp);
244 if (m_visionUpdates.empty() || timestamp < m_visionUpdates.begin()->first) {
245 return m_odometryPoseBuffer.Sample(timestamp);
253 auto floorIter = m_visionUpdates.upper_bound(timestamp);
255 auto visionUpdate = floorIter->second;
258 auto odometryEstimate = m_odometryPoseBuffer.Sample(timestamp);
262 if (odometryEstimate) {
263 return visionUpdate.Compensate(*odometryEstimate);
289 wpi::units::second_t timestamp) {
292 if (m_odometryPoseBuffer.GetInternalBuffer().empty() ||
293 m_odometryPoseBuffer.GetInternalBuffer().front().first -
300 CleanUpVisionUpdates();
304 auto odometrySample = m_odometryPoseBuffer.Sample(timestamp);
306 if (!odometrySample) {
312 auto visionSample =
SampleAt(timestamp);
320 auto transform = visionRobotPose - visionSample.value();
325 Eigen::Vector3d k_times_transform =
326 m_vision_K * Eigen::Vector3d{transform.X().value(),
327 transform.Y().value(),
328 transform.Rotation().Radians().value()};
332 wpi::units::meter_t{k_times_transform(0)},
333 wpi::units::meter_t{k_times_transform(1)},
334 Rotation2d{wpi::units::radian_t{k_times_transform(2)}}};
337 VisionUpdate visionUpdate{*visionSample + scaledTransform, *odometrySample};
338 m_visionUpdates[timestamp] = visionUpdate;
341 auto firstAfter = m_visionUpdates.upper_bound(timestamp);
342 m_visionUpdates.erase(firstAfter, m_visionUpdates.end());
346 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
378 const Pose2d& visionRobotPose, wpi::units::second_t timestamp,
394 const WheelPositions& wheelPositions) {
411 const WheelPositions& wheelPositions) {
412 auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions);
414 m_odometryPoseBuffer.AddSample(currentTime, odometryEstimate);
416 if (m_visionUpdates.empty()) {
417 m_poseEstimate = odometryEstimate;
419 auto visionUpdate = m_visionUpdates.rbegin()->second;
420 m_poseEstimate = visionUpdate.Compensate(odometryEstimate);
430 void CleanUpVisionUpdates() {
432 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
437 wpi::units::second_t oldestOdometryTimestamp =
438 m_odometryPoseBuffer.GetInternalBuffer().front().first;
441 if (m_visionUpdates.empty() ||
442 oldestOdometryTimestamp < m_visionUpdates.begin()->first) {
451 auto newestNeededVisionUpdate =
452 m_visionUpdates.upper_bound(oldestOdometryTimestamp);
453 --newestNeededVisionUpdate;
456 m_visionUpdates.erase(m_visionUpdates.begin(), newestNeededVisionUpdate);
459 struct VisionUpdate {
474 Pose2d Compensate(
const Pose2d& pose)
const {
475 auto delta = pose - odometryPose;
476 return visionPose + delta;
480 static constexpr wpi::units::second_t kBufferDuration = 1.5_s;
482 Odometry<WheelPositions, WheelVelocities, WheelAccelerations>& m_odometry;
488 Eigen::DiagonalMatrix<double, 3> m_vision_K =
489 Eigen::DiagonalMatrix<double, 3>::Zero();
492 TimeInterpolatableBuffer<Pose2d> m_odometryPoseBuffer{kBufferDuration};
498 std::map<wpi::units::second_t, VisionUpdate> m_visionUpdates;
500 Pose2d m_poseEstimate;
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel v...
Definition Kinematics.hpp:26
static void ReportUsage(std::string_view resource, std::string_view data)
Definition MathShared.hpp:61
static wpi::units::second_t GetTimestamp()
Definition MathShared.hpp:65
Class for odometry.
Definition Odometry.hpp:31
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
Pose2d UpdateWithTime(wpi::units::second_t currentTime, const Rotation2d &gyroAngle, const WheelPositions &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition PoseEstimator.hpp:409
void AddVisionMeasurement(const Pose2d &visionRobotPose, wpi::units::second_t timestamp, const wpi::util::array< double, 3 > &visionMeasurementStdDevs)
Adds a vision measurement to the Kalman Filter.
Definition PoseEstimator.hpp:377
void ResetPosition(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition PoseEstimator.hpp:121
Pose2d Update(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition PoseEstimator.hpp:393
void ResetTranslation(const Translation2d &translation)
Resets the robot's translation.
Definition PoseEstimator.hpp:151
Pose2d GetEstimatedPosition() const
Gets the estimated robot pose.
Definition PoseEstimator.hpp:217
std::optional< Pose2d > SampleAt(wpi::units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
Definition PoseEstimator.hpp:226
PoseEstimator(Kinematics< WheelPositions, WheelVelocities, WheelAccelerations > &kinematics, Odometry< WheelPositions, WheelVelocities, WheelAccelerations > &odometry, const wpi::util::array< double, 3 > &stateStdDevs, const wpi::util::array< double, 3 > &visionMeasurementStdDevs)
Constructs a PoseEstimator.
Definition PoseEstimator.hpp:66
void AddVisionMeasurement(const Pose2d &visionRobotPose, wpi::units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition PoseEstimator.hpp:288
void ResetRotation(const Rotation2d &rotation)
Resets the robot's rotation.
Definition PoseEstimator.hpp:186
void SetVisionMeasurementStdDevs(const wpi::util::array< double, 3 > &visionMeasurementStdDevs)
Sets the pose estimator's trust in vision measurements.
Definition PoseEstimator.hpp:91
void ResetPose(const Pose2d &pose)
Resets the robot's pose.
Definition PoseEstimator.hpp:135
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
Represents a translation in 2D space.
Definition Translation2d.hpp:30
This class is a wrapper around std::array that does compile time size checking.
Definition array.hpp:26
Definition LinearSystem.hpp:20
constexpr empty_array_t empty_array
Definition array.hpp:16