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