42template <
typename WheelSpeeds,
typename WheelPositions>
66 : m_odometry(odometry) {
67 for (
size_t i = 0; i < 3; ++i) {
68 m_q[i] = stateStdDevs[i] * stateStdDevs[i];
71 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
87 for (
size_t i = 0; i < 3; ++i) {
88 r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i];
93 for (
size_t row = 0; row < 3; ++row) {
94 if (m_q[row] == 0.0) {
95 m_visionK(row, row) = 0.0;
98 m_q[row] / (m_q[row] + std::sqrt(m_q[row] * r[row]));
114 const WheelPositions& wheelPositions,
const Pose2d& pose) {
116 m_odometry.ResetPosition(gyroAngle, wheelPositions, pose);
117 m_odometryPoseBuffer.Clear();
118 m_visionUpdates.clear();
119 m_poseEstimate = m_odometry.GetPose();
128 m_odometry.ResetPose(pose);
129 m_odometryPoseBuffer.Clear();
130 m_visionUpdates.clear();
131 m_poseEstimate = m_odometry.GetPose();
140 m_odometry.ResetTranslation(translation);
141 m_odometryPoseBuffer.Clear();
142 m_visionUpdates.clear();
143 m_poseEstimate = m_odometry.GetPose();
152 m_odometry.ResetRotation(rotation);
153 m_odometryPoseBuffer.Clear();
154 m_visionUpdates.clear();
155 m_poseEstimate = m_odometry.GetPose();
172 std::optional<Pose2d>
SampleAt(units::second_t timestamp)
const {
174 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
181 units::second_t oldestOdometryTimestamp =
182 m_odometryPoseBuffer.GetInternalBuffer().front().first;
183 units::second_t newestOdometryTimestamp =
184 m_odometryPoseBuffer.GetInternalBuffer().back().first;
186 std::clamp(timestamp, oldestOdometryTimestamp, newestOdometryTimestamp);
190 if (m_visionUpdates.empty() || timestamp < m_visionUpdates.begin()->first) {
191 return m_odometryPoseBuffer.Sample(timestamp);
199 auto floorIter = m_visionUpdates.upper_bound(timestamp);
201 auto visionUpdate = floorIter->second;
204 auto odometryEstimate = m_odometryPoseBuffer.Sample(timestamp);
208 if (odometryEstimate) {
209 return visionUpdate.Compensate(*odometryEstimate);
235 units::second_t timestamp) {
238 if (m_odometryPoseBuffer.GetInternalBuffer().empty() ||
239 m_odometryPoseBuffer.GetInternalBuffer().front().first -
246 CleanUpVisionUpdates();
250 auto odometrySample = m_odometryPoseBuffer.Sample(timestamp);
252 if (!odometrySample) {
258 auto visionSample = SampleAt(timestamp);
266 auto twist = visionSample.value().Log(visionRobotPose);
271 Eigen::Vector3d k_times_twist =
272 m_visionK * Eigen::Vector3d{twist.dx.value(), twist.dy.value(),
273 twist.dtheta.value()};
276 Twist2d scaledTwist{units::meter_t{k_times_twist(0)},
277 units::meter_t{k_times_twist(1)},
278 units::radian_t{k_times_twist(2)}};
281 VisionUpdate visionUpdate{visionSample->Exp(scaledTwist), *odometrySample};
282 m_visionUpdates[timestamp] = visionUpdate;
285 auto firstAfter = m_visionUpdates.upper_bound(timestamp);
286 m_visionUpdates.erase(firstAfter, m_visionUpdates.end());
290 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
322 const Pose2d& visionRobotPose, units::second_t timestamp,
324 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
325 AddVisionMeasurement(visionRobotPose, timestamp);
338 const WheelPositions& wheelPositions) {
355 const WheelPositions& wheelPositions) {
356 auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions);
358 m_odometryPoseBuffer.AddSample(currentTime, odometryEstimate);
360 if (m_visionUpdates.empty()) {
361 m_poseEstimate = odometryEstimate;
363 auto visionUpdate = m_visionUpdates.rbegin()->second;
364 m_poseEstimate = visionUpdate.Compensate(odometryEstimate);
367 return GetEstimatedPosition();
374 void CleanUpVisionUpdates() {
376 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
381 units::second_t oldestOdometryTimestamp =
382 m_odometryPoseBuffer.GetInternalBuffer().front().first;
385 if (m_visionUpdates.empty() ||
386 oldestOdometryTimestamp < m_visionUpdates.begin()->first) {
395 auto newestNeededVisionUpdate =
396 m_visionUpdates.upper_bound(oldestOdometryTimestamp);
397 --newestNeededVisionUpdate;
400 m_visionUpdates.erase(m_visionUpdates.begin(), newestNeededVisionUpdate);
403 struct VisionUpdate {
418 Pose2d Compensate(
const Pose2d& pose)
const {
419 auto delta = pose - odometryPose;
420 return visionPose + delta;
424 static constexpr units::second_t kBufferDuration = 1.5_s;
426 Odometry<WheelSpeeds, WheelPositions>& m_odometry;
428 Eigen::Matrix3d m_visionK = Eigen::Matrix3d::Zero();
431 TimeInterpolatableBuffer<Pose2d> m_odometryPoseBuffer{kBufferDuration};
435 std::map<units::second_t, VisionUpdate> m_visionUpdates;
437 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:43
void ResetRotation(const Rotation2d &rotation)
Resets the robot's rotation.
Definition PoseEstimator.h:151
void SetVisionMeasurementStdDevs(const wpi::array< double, 3 > &visionMeasurementStdDevs)
Sets the pose estimator's trust in vision measurements.
Definition PoseEstimator.h:84
Pose2d Update(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition PoseEstimator.h:337
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:172
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:321
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:62
void AddVisionMeasurement(const Pose2d &visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition PoseEstimator.h:234
void ResetPose(const Pose2d &pose)
Resets the robot's pose.
Definition PoseEstimator.h:127
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:353
void ResetPosition(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition PoseEstimator.h:113
Pose2d GetEstimatedPosition() const
Gets the estimated robot pose.
Definition PoseEstimator.h:163
void ResetTranslation(const Translation2d &translation)
Resets the robot's translation.
Definition PoseEstimator.h:139
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:29
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:79
constexpr empty_array_t empty_array
Definition array.h:16
A change in distance along a 2D arc since the last pose update.
Definition Twist2d.h:22