WPILibC++ 2026.2.1
Loading...
Searching...
No Matches
PoseEstimator.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <map>
8#include <optional>
9#include <vector>
10
11#include <Eigen/Core>
12#include <wpi/SymbolExports.h>
13#include <wpi/array.h>
14
15#include "frc/geometry/Pose2d.h"
22#include "units/time.h"
23#include "wpimath/MathShared.h"
24
25namespace frc {
26
27/**
28 * This class wraps odometry to fuse latency-compensated
29 * vision measurements with encoder measurements. Robot code should not use this
30 * directly- Instead, use the particular type for your drivetrain (e.g.,
31 * DifferentialDrivePoseEstimator). It will correct for noisy vision
32 * measurements and encoder drift. It is intended to be an easy drop-in for
33 * Odometry.
34 *
35 * Update() should be called every robot loop.
36 *
37 * AddVisionMeasurement() can be called as infrequently as you want; if you
38 * never call it, then this class will behave like regular encoder odometry.
39 *
40 * @tparam WheelSpeeds Wheel speeds type.
41 * @tparam WheelPositions Wheel positions type.
42 */
43template <typename WheelSpeeds, typename WheelPositions>
45 public:
46 /**
47 * Constructs a PoseEstimator.
48 *
49 * @warning The initial pose estimate will always be the default pose,
50 * regardless of the odometry's current pose.
51 *
52 * @param kinematics A correctly-configured kinematics object for your
53 * drivetrain.
54 * @param odometry A correctly-configured odometry object for your drivetrain.
55 * @param stateStdDevs Standard deviations of the pose estimate (x position in
56 * meters, y position in meters, and heading in radians). Increase these
57 * numbers to trust your state estimate less.
58 * @param visionMeasurementStdDevs Standard deviations of the vision pose
59 * measurement (x position in meters, y position in meters, and heading in
60 * radians). Increase these numbers to trust the vision pose measurement
61 * less.
62 */
65 const wpi::array<double, 3>& stateStdDevs,
66 const wpi::array<double, 3>& visionMeasurementStdDevs)
67 : m_odometry(odometry) {
68 for (size_t i = 0; i < 3; ++i) {
69 m_q[i] = stateStdDevs[i] * stateStdDevs[i];
70 }
71
72 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
75 }
76
77 /**
78 * Sets the pose estimator's trust in vision measurements. This might be used
79 * to change trust in vision measurements after the autonomous period, or to
80 * change trust as distance to a vision target increases.
81 *
82 * @param visionMeasurementStdDevs Standard deviations of the vision pose
83 * measurement (x position in meters, y position in meters, and heading in
84 * radians). Increase these numbers to trust the vision pose measurement
85 * less.
86 */
88 const wpi::array<double, 3>& visionMeasurementStdDevs) {
90 for (size_t i = 0; i < 3; ++i) {
91 r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i];
92 }
93
94 // Solve for closed form Kalman gain for continuous Kalman filter with A = 0
95 // and C = I. See wpimath/algorithms.md.
96 for (size_t row = 0; row < 3; ++row) {
97 if (m_q[row] == 0.0) {
98 m_visionK(row, row) = 0.0;
99 } else {
100 m_visionK(row, row) =
101 m_q[row] / (m_q[row] + std::sqrt(m_q[row] * r[row]));
102 }
103 }
104 }
105
106 /**
107 * Resets the robot's position on the field.
108 *
109 * The gyroscope angle does not need to be reset in the user's robot code.
110 * The library automatically takes care of offsetting the gyro angle.
111 *
112 * @param gyroAngle The current gyro angle.
113 * @param wheelPositions The distances traveled by the encoders.
114 * @param pose The estimated pose of the robot on the field.
115 */
116 void ResetPosition(const Rotation2d& gyroAngle,
117 const WheelPositions& wheelPositions, const Pose2d& pose) {
118 // Reset state estimate and error covariance
119 m_odometry.ResetPosition(gyroAngle, wheelPositions, pose);
120 m_odometryPoseBuffer.Clear();
121 m_visionUpdates.clear();
122 m_poseEstimate = m_odometry.GetPose();
123 }
124
125 /**
126 * Resets the robot's pose.
127 *
128 * @param pose The pose to reset to.
129 */
130 void ResetPose(const Pose2d& pose) {
131 m_odometry.ResetPose(pose);
132 m_odometryPoseBuffer.Clear();
133 m_visionUpdates.clear();
134 m_poseEstimate = m_odometry.GetPose();
135 }
136
137 /**
138 * Resets the robot's translation.
139 *
140 * @param translation The pose to translation to.
141 */
142#if defined(__GNUC__) && !defined(__clang__)
143#pragma GCC diagnostic push
144#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
145#endif // defined(__GNUC__) && !defined(__clang__)
146 void ResetTranslation(const Translation2d& translation) {
147 m_odometry.ResetTranslation(translation);
148
149 const std::optional<std::pair<units::second_t, VisionUpdate>>
150 latestVisionUpdate =
151 m_visionUpdates.empty() ? std::nullopt
152 : std::optional{*m_visionUpdates.crbegin()};
153 m_odometryPoseBuffer.Clear();
154 m_visionUpdates.clear();
155
156 if (latestVisionUpdate) {
157 // apply vision compensation to the pose rotation
158 const VisionUpdate visionUpdate{
159 Pose2d{translation, latestVisionUpdate->second.visionPose.Rotation()},
160 Pose2d{translation,
161 latestVisionUpdate->second.odometryPose.Rotation()}};
162 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
163 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
164 } else {
165 m_poseEstimate = m_odometry.GetPose();
166 }
167 }
168#if defined(__GNUC__) && !defined(__clang__)
169#pragma GCC diagnostic pop
170#endif // defined(__GNUC__) && !defined(__clang__)
171
172 /**
173 * Resets the robot's rotation.
174 *
175 * @param rotation The rotation to reset to.
176 */
177#if defined(__GNUC__) && !defined(__clang__)
178#pragma GCC diagnostic push
179#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
180#endif // defined(__GNUC__) && !defined(__clang__)
181 void ResetRotation(const Rotation2d& rotation) {
182 m_odometry.ResetRotation(rotation);
183
184 const std::optional<std::pair<units::second_t, VisionUpdate>>
185 latestVisionUpdate =
186 m_visionUpdates.empty() ? std::nullopt
187 : std::optional{*m_visionUpdates.crbegin()};
188 m_odometryPoseBuffer.Clear();
189 m_visionUpdates.clear();
190
191 if (latestVisionUpdate) {
192 // apply vision compensation to the pose translation
193 const VisionUpdate visionUpdate{
194 Pose2d{latestVisionUpdate->second.visionPose.Translation(), rotation},
195 Pose2d{latestVisionUpdate->second.odometryPose.Translation(),
196 rotation}};
197 m_visionUpdates[latestVisionUpdate->first] = visionUpdate;
198 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
199 } else {
200 m_poseEstimate = m_odometry.GetPose();
201 }
202 }
203#if defined(__GNUC__) && !defined(__clang__)
204#pragma GCC diagnostic pop
205#endif // defined(__GNUC__) && !defined(__clang__)
206
207 /**
208 * Gets the estimated robot pose.
209 *
210 * @return The estimated robot pose in meters.
211 */
212 Pose2d GetEstimatedPosition() const { return m_poseEstimate; }
213
214 /**
215 * Return the pose at a given timestamp, if the buffer is not empty.
216 *
217 * @param timestamp The pose's timestamp.
218 * @return The pose at the given timestamp (or std::nullopt if the buffer is
219 * empty).
220 */
221 std::optional<Pose2d> SampleAt(units::second_t timestamp) const {
222 // Step 0: If there are no odometry updates to sample, skip.
223 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
224 return std::nullopt;
225 }
226
227 // Step 1: Make sure timestamp matches the sample from the odometry pose
228 // buffer. (When sampling, the buffer will always use a timestamp
229 // between the first and last timestamps)
230 units::second_t oldestOdometryTimestamp =
231 m_odometryPoseBuffer.GetInternalBuffer().front().first;
232 units::second_t newestOdometryTimestamp =
233 m_odometryPoseBuffer.GetInternalBuffer().back().first;
234 timestamp =
235 std::clamp(timestamp, oldestOdometryTimestamp, newestOdometryTimestamp);
236
237 // Step 2: If there are no applicable vision updates, use the odometry-only
238 // information.
239 if (m_visionUpdates.empty() || timestamp < m_visionUpdates.begin()->first) {
240 return m_odometryPoseBuffer.Sample(timestamp);
241 }
242
243 // Step 3: Get the latest vision update from before or at the timestamp to
244 // sample at.
245 // First, find the iterator past the sample timestamp, then go back one.
246 // Note that upper_bound() won't return begin() because we check begin()
247 // earlier.
248 auto floorIter = m_visionUpdates.upper_bound(timestamp);
249 --floorIter;
250 auto visionUpdate = floorIter->second;
251
252 // Step 4: Get the pose measured by odometry at the time of the sample.
253 auto odometryEstimate = m_odometryPoseBuffer.Sample(timestamp);
254
255 // Step 5: Apply the vision compensation to the odometry pose.
256 // TODO Replace with std::optional::transform() in C++23
257 if (odometryEstimate) {
258 return visionUpdate.Compensate(*odometryEstimate);
259 }
260 return std::nullopt;
261 }
262
263 /**
264 * Adds a vision measurement to the Kalman Filter. This will correct
265 * the odometry pose estimate while still accounting for measurement noise.
266 *
267 * This method can be called as infrequently as you want, as long as you are
268 * calling Update() every loop.
269 *
270 * To promote stability of the pose estimate and make it robust to bad vision
271 * data, we recommend only adding vision measurements that are already within
272 * one meter or so of the current pose estimate.
273 *
274 * @param visionRobotPose The pose of the robot as measured by the vision
275 * camera.
276 * @param timestamp The timestamp of the vision measurement in seconds. Note
277 * that if you don't use your own time source by calling UpdateWithTime(),
278 * then you must use a timestamp with an epoch since FPGA startup (i.e.,
279 * the epoch of this timestamp is the same epoch as
280 * frc::Timer::GetTimestamp(). This means that you should use
281 * frc::Timer::GetTimestamp() as your time source in this case.
282 */
283 void AddVisionMeasurement(const Pose2d& visionRobotPose,
284 units::second_t timestamp) {
285 // Step 0: If this measurement is old enough to be outside the pose buffer's
286 // timespan, skip.
287 if (m_odometryPoseBuffer.GetInternalBuffer().empty() ||
288 m_odometryPoseBuffer.GetInternalBuffer().front().first -
289 kBufferDuration >
290 timestamp) {
291 return;
292 }
293
294 // Step 1: Clean up any old entries
295 CleanUpVisionUpdates();
296
297 // Step 2: Get the pose measured by odometry at the moment the vision
298 // measurement was made.
299 auto odometrySample = m_odometryPoseBuffer.Sample(timestamp);
300
301 if (!odometrySample) {
302 return;
303 }
304
305 // Step 3: Get the vision-compensated pose estimate at the moment the vision
306 // measurement was made.
307 auto visionSample = SampleAt(timestamp);
308
309 if (!visionSample) {
310 return;
311 }
312
313 // Step 4: Measure the transform between the old pose estimate and the
314 // vision transform.
315 auto transform = visionRobotPose - visionSample.value();
316
317 // Step 5: We should not trust the transform entirely, so instead we scale
318 // this transform by a Kalman gain matrix representing how much we trust
319 // vision measurements compared to our current pose.
320 Eigen::Vector3d k_times_transform =
321 m_visionK * Eigen::Vector3d{transform.X().value(),
322 transform.Y().value(),
323 transform.Rotation().Radians().value()};
324
325 // Step 6: Convert back to Transform2d.
326 Transform2d scaledTransform{
327 units::meter_t{k_times_transform(0)},
328 units::meter_t{k_times_transform(1)},
329 Rotation2d{units::radian_t{k_times_transform(2)}}};
330
331 // Step 7: Calculate and record the vision update.
332 VisionUpdate visionUpdate{*visionSample + scaledTransform, *odometrySample};
333 m_visionUpdates[timestamp] = visionUpdate;
334
335 // Step 8: Remove later vision measurements. (Matches previous behavior)
336 auto firstAfter = m_visionUpdates.upper_bound(timestamp);
337 m_visionUpdates.erase(firstAfter, m_visionUpdates.end());
338
339 // Step 9: Update latest pose estimate. Since we cleared all updates after
340 // this vision update, it's guaranteed to be the latest vision update.
341 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
342 }
343
344 /**
345 * Adds a vision measurement to the Kalman Filter. This will correct
346 * the odometry pose estimate while still accounting for measurement noise.
347 *
348 * This method can be called as infrequently as you want, as long as you are
349 * calling Update() every loop.
350 *
351 * To promote stability of the pose estimate and make it robust to bad vision
352 * data, we recommend only adding vision measurements that are already within
353 * one meter or so of the current pose estimate.
354 *
355 * Note that the vision measurement standard deviations passed into this
356 * method will continue to apply to future measurements until a subsequent
357 * call to SetVisionMeasurementStdDevs() or this method.
358 *
359 * @param visionRobotPose The pose of the robot as measured by the vision
360 * camera.
361 * @param timestamp The timestamp of the vision measurement in seconds. Note
362 * that if you don't use your own time source by calling UpdateWithTime(),
363 * then you must use a timestamp with an epoch since FPGA startup (i.e.,
364 * the epoch of this timestamp is the same epoch as
365 * frc::Timer::GetTimestamp(). This means that you should use
366 * frc::Timer::GetTimestamp() as your time source in this case.
367 * @param visionMeasurementStdDevs Standard deviations of the vision pose
368 * measurement (x position in meters, y position in meters, and heading in
369 * radians). Increase these numbers to trust the vision pose measurement
370 * less.
371 */
373 const Pose2d& visionRobotPose, units::second_t timestamp,
374 const wpi::array<double, 3>& visionMeasurementStdDevs) {
375 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
376 AddVisionMeasurement(visionRobotPose, timestamp);
377 }
378
379 /**
380 * Updates the pose estimator with wheel encoder and gyro information. This
381 * should be called every loop.
382 *
383 * @param gyroAngle The current gyro angle.
384 * @param wheelPositions The distances traveled by the encoders.
385 *
386 * @return The estimated pose of the robot in meters.
387 */
388 Pose2d Update(const Rotation2d& gyroAngle,
389 const WheelPositions& wheelPositions) {
390 return UpdateWithTime(wpi::math::MathSharedStore::GetTimestamp(), gyroAngle,
391 wheelPositions);
392 }
393
394 /**
395 * Updates the pose estimator with wheel encoder and gyro information. This
396 * should be called every loop.
397 *
398 * @param currentTime The time at which this method was called.
399 * @param gyroAngle The current gyro angle.
400 * @param wheelPositions The distances traveled by the encoders.
401 *
402 * @return The estimated pose of the robot in meters.
403 */
404 Pose2d UpdateWithTime(units::second_t currentTime,
405 const Rotation2d& gyroAngle,
406 const WheelPositions& wheelPositions) {
407 auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions);
408
409 m_odometryPoseBuffer.AddSample(currentTime, odometryEstimate);
410
411 if (m_visionUpdates.empty()) {
412 m_poseEstimate = odometryEstimate;
413 } else {
414 auto visionUpdate = m_visionUpdates.rbegin()->second;
415 m_poseEstimate = visionUpdate.Compensate(odometryEstimate);
416 }
417
418 return GetEstimatedPosition();
419 }
420
421 private:
422 /**
423 * Removes stale vision updates that won't affect sampling.
424 */
425 void CleanUpVisionUpdates() {
426 // Step 0: If there are no odometry samples, skip.
427 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
428 return;
429 }
430
431 // Step 1: Find the oldest timestamp that needs a vision update.
432 units::second_t oldestOdometryTimestamp =
433 m_odometryPoseBuffer.GetInternalBuffer().front().first;
434
435 // Step 2: If there are no vision updates before that timestamp, skip.
436 if (m_visionUpdates.empty() ||
437 oldestOdometryTimestamp < m_visionUpdates.begin()->first) {
438 return;
439 }
440
441 // Step 3: Find the newest vision update timestamp before or at the oldest
442 // timestamp.
443 // First, find the iterator past the oldest odometry timestamp, then go
444 // back one. Note that upper_bound() won't return begin() because we check
445 // begin() earlier.
446 auto newestNeededVisionUpdate =
447 m_visionUpdates.upper_bound(oldestOdometryTimestamp);
448 --newestNeededVisionUpdate;
449
450 // Step 4: Remove all entries strictly before the newest timestamp we need.
451 m_visionUpdates.erase(m_visionUpdates.begin(), newestNeededVisionUpdate);
452 }
453
454 struct VisionUpdate {
455 // The vision-compensated pose estimate
456 Pose2d visionPose;
457
458 // The pose estimated based solely on odometry
459 Pose2d odometryPose;
460
461 /**
462 * Returns the vision-compensated version of the pose. Specifically, changes
463 * the pose from being relative to this record's odometry pose to being
464 * relative to this record's vision pose.
465 *
466 * @param pose The pose to compensate.
467 * @return The compensated pose.
468 */
469 Pose2d Compensate(const Pose2d& pose) const {
470 auto delta = pose - odometryPose;
471 return visionPose + delta;
472 }
473 };
474
475 static constexpr units::second_t kBufferDuration = 1.5_s;
476
477 Odometry<WheelSpeeds, WheelPositions>& m_odometry;
479 Eigen::Matrix3d m_visionK = Eigen::Matrix3d::Zero();
480
481 // Maps timestamps to odometry-only pose estimates
482 TimeInterpolatableBuffer<Pose2d> m_odometryPoseBuffer{kBufferDuration};
483 // Maps timestamps to vision updates
484 // Always contains one entry before the oldest entry in m_odometryPoseBuffer,
485 // unless there have been no vision measurements after the last reset. May
486 // contain one entry while m_odometryPoseBuffer is empty to correct for
487 // translation/rotation after a call to ResetRotation/ResetTranslation.
488 std::map<units::second_t, VisionUpdate> m_visionUpdates;
489
490 Pose2d m_poseEstimate;
491};
492
493} // namespace frc
#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:181
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:388
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:221
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:372
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:283
void ResetPose(const Pose2d &pose)
Resets the robot's pose.
Definition PoseEstimator.h:130
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:404
void ResetPosition(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition PoseEstimator.h:116
Pose2d GetEstimatedPosition() const
Gets the estimated robot pose.
Definition PoseEstimator.h:212
void ResetTranslation(const Translation2d &translation)
Resets the robot's translation.
Definition PoseEstimator.h:146
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
Represents a transformation for a Pose2d in the pose's frame.
Definition Transform2d.h:21
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
Definition CAN.h:11
constexpr empty_array_t empty_array
Definition array.h:16