PhotonVision C++ v2026.0.0-alpha-2
Loading...
Searching...
No Matches
PhotonPoseEstimator.h
Go to the documentation of this file.
1/*
2 * MIT License
3 *
4 * Copyright (c) PhotonVision
5 *
6 * Permission is hereby granted, free of charge, to any person obtaining a copy
7 * of this software and associated documentation files (the "Software"), to deal
8 * in the Software without restriction, including without limitation the rights
9 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
10 * copies of the Software, and to permit persons to whom the Software is
11 * furnished to do so, subject to the following conditions:
12 *
13 * The above copyright notice and this permission notice shall be included in
14 * all copies or substantial portions of the Software.
15 *
16 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
17 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
18 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
19 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
20 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
21 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
22 * SOFTWARE.
23 */
24
25#pragma once
26
27#include <memory>
28
29#include <frc/apriltag/AprilTagFieldLayout.h>
30#include <frc/geometry/Pose3d.h>
31#include <frc/geometry/Rotation3d.h>
32#include <frc/geometry/Transform3d.h>
33#include <frc/interpolation/TimeInterpolatableBuffer.h>
34#include <opencv2/core/mat.hpp>
35
36#include "photon/PhotonCamera.h"
42
43namespace photon {
55
60
62 /** The estimated pose */
63 frc::Pose3d estimatedPose;
64 /** The estimated time the frame used to derive the robot pose was taken, in
65 * the same timebase as the RoboRIO FPGA Timestamp */
66 units::second_t timestamp;
67
68 /** A list of the targets used to compute this pose */
69 wpi::SmallVector<PhotonTrackedTarget, 10> targetsUsed;
70
71 /** The strategy actually used to produce this pose */
73
74 EstimatedRobotPose(frc::Pose3d pose_, units::second_t time_,
75 std::span<const PhotonTrackedTarget> targets,
76 PoseStrategy strategy_)
77 : estimatedPose(pose_),
78 timestamp(time_),
79 targetsUsed(targets.data(), targets.data() + targets.size()),
80 strategy(strategy_) {}
81};
82
83/**
84 * The PhotonPoseEstimator class filters or combines readings from all the
85 * fiducials visible at a given timestamp on the field to produce a single robot
86 * in field pose, using the strategy set below. Example usage can be found in
87 * our apriltagExample example project.
88 */
90 public:
91 /**
92 * Create a new PhotonPoseEstimator.
93 *
94 * @param aprilTags A AprilTagFieldLayout linking AprilTag IDs to Pose3ds with
95 * respect to the FIRST field.
96 * @param strategy The strategy it should use to determine the best pose.
97 * @param robotToCamera Transform3d from the center of the robot to the camera
98 * mount positions (ie, robot ➔ camera).
99 */
100 explicit PhotonPoseEstimator(frc::AprilTagFieldLayout aprilTags,
101 PoseStrategy strategy,
102 frc::Transform3d robotToCamera);
103
104 /**
105 * Get the AprilTagFieldLayout being used by the PositionEstimator.
106 *
107 * @return the AprilTagFieldLayout
108 */
109 frc::AprilTagFieldLayout GetFieldLayout() const { return aprilTags; }
110
111 /**
112 * Get the Position Estimation Strategy being used by the Position Estimator.
113 *
114 * @return the strategy
115 */
116 PoseStrategy GetPoseStrategy() const { return strategy; }
117
118 /**
119 * Set the Position Estimation Strategy used by the Position Estimator.
120 *
121 * @param strategy the strategy to set
122 */
123 inline void SetPoseStrategy(PoseStrategy strat) {
124 if (strategy != strat) {
125 InvalidatePoseCache();
126 }
127 strategy = strat;
128 }
129
130 /**
131 * Set the Position Estimation Strategy used in multi-tag mode when
132 * only one tag can be seen. Must NOT be MULTI_TAG_PNP
133 *
134 * @param strategy the strategy to set
135 */
137
138 /**
139 * Return the reference position that is being used by the estimator.
140 *
141 * @return the referencePose
142 */
143 frc::Pose3d GetReferencePose() const { return referencePose; }
144
145 /**
146 * Update the stored reference pose for use when using the
147 * CLOSEST_TO_REFERENCE_POSE strategy.
148 *
149 * @param referencePose the referencePose to set
150 */
151 inline void SetReferencePose(frc::Pose3d referencePose) {
152 if (this->referencePose != referencePose) {
153 InvalidatePoseCache();
154 }
155 this->referencePose = referencePose;
156 }
157
158 /**
159 * @return The current transform from the center of the robot to the camera
160 * mount position.
161 */
162 inline frc::Transform3d GetRobotToCameraTransform() {
163 return m_robotToCamera;
164 }
165
166 /**
167 * Useful for pan and tilt mechanisms, or cameras on turrets
168 *
169 * @param robotToCamera The current transform from the center of the robot to
170 * the camera mount position.
171 */
172 inline void SetRobotToCameraTransform(frc::Transform3d robotToCamera) {
173 m_robotToCamera = robotToCamera;
174 }
175
176 /**
177 * Update the stored last pose. Useful for setting the initial estimate when
178 * using the CLOSEST_TO_LAST_POSE strategy.
179 *
180 * @param lastPose the lastPose to set
181 */
182 inline void SetLastPose(frc::Pose3d lastPose) { this->lastPose = lastPose; }
183
184 /**
185 * Add robot heading data to the buffer. Must be called periodically for the
186 * PNP_DISTANCE_TRIG_SOLVE strategy.
187 *
188 * @param timestamp Timestamp of the robot heading data.
189 * @param heading Field-relative heading at the given timestamp. Standard
190 * WPILIB field coordinates.
191 */
192 inline void AddHeadingData(units::second_t timestamp,
193 frc::Rotation2d heading) {
194 this->headingBuffer.AddSample(timestamp, heading);
195 }
196
197 /**
198 * Add robot heading data to the buffer. Must be called periodically for the
199 * PNP_DISTANCE_TRIG_SOLVE strategy.
200 *
201 * @param timestamp Timestamp of the robot heading data.
202 * @param heading Field-relative heading at the given timestamp. Standard
203 * WPILIB coordinates.
204 */
205 inline void AddHeadingData(units::second_t timestamp,
206 frc::Rotation3d heading) {
207 AddHeadingData(timestamp, heading.ToRotation2d());
208 }
209
210 /**
211 * Clears all heading data in the buffer, and adds a new seed. Useful for
212 * preventing estimates from utilizing heading data provided prior to a pose
213 * or rotation reset.
214 *
215 * @param timestamp Timestamp of the robot heading data.
216 * @param heading Field-relative robot heading at given timestamp. Standard
217 * WPILIB field coordinates.
218 */
219 inline void ResetHeadingData(units::second_t timestamp,
220 frc::Rotation2d heading) {
221 headingBuffer.Clear();
222 AddHeadingData(timestamp, heading);
223 }
224
225 /**
226 * Clears all heading data in the buffer, and adds a new seed. Useful for
227 * preventing estimates from utilizing heading data provided prior to a pose
228 * or rotation reset.
229 *
230 * @param timestamp Timestamp of the robot heading data.
231 * @param heading Field-relative robot heading at given timestamp. Standard
232 * WPILIB field coordinates.
233 */
234 inline void ResetHeadingData(units::second_t timestamp,
235 frc::Rotation3d heading) {
236 ResetHeadingData(timestamp, heading.ToRotation2d());
237 }
238
239 /**
240 * Update the pose estimator. If updating multiple times per loop, you should
241 * call this exactly once per new result, in order of increasing result
242 * timestamp.
243 *
244 * @param result The vision targeting result to process
245 * @param cameraIntrinsics The camera calibration pinhole coefficients matrix.
246 * Only required if doing multitag-on-rio, and may be nullopt otherwise.
247 * @param distCoeffsData The camera calibration distortion coefficients. Only
248 * required if doing multitag-on-rio, and may be nullopt otherwise.
249 * @param constrainedPnpParams Constrained SolvePNP params, if needed.
250 */
251 std::optional<EstimatedRobotPose> Update(
252 const photon::PhotonPipelineResult& result,
253 std::optional<photon::PhotonCamera::CameraMatrix> cameraMatrixData =
254 std::nullopt,
255 std::optional<photon::PhotonCamera::DistortionMatrix> coeffsData =
256 std::nullopt,
257 std::optional<ConstrainedSolvepnpParams> constrainedPnpParams =
258 std::nullopt);
259
260 private:
261 frc::AprilTagFieldLayout aprilTags;
262 PoseStrategy strategy;
263 PoseStrategy multiTagFallbackStrategy = LOWEST_AMBIGUITY;
264
265 frc::Transform3d m_robotToCamera;
266
267 frc::Pose3d lastPose;
268 frc::Pose3d referencePose;
269
270 units::second_t poseCacheTimestamp;
271
272 frc::TimeInterpolatableBuffer<frc::Rotation2d> headingBuffer;
273
274 inline static int InstanceCount = 1;
275
276 inline void InvalidatePoseCache() { poseCacheTimestamp = -1_s; }
277
278 /**
279 * Internal convenience method for using a fallback strategy for update().
280 * This should only be called after timestamp checks have been done by another
281 * update() overload.
282 *
283 * @param cameraResult The latest pipeline result from the camera
284 * @param strategy The pose strategy to use
285 * @return an EstimatedRobotPose with an estimated pose, timestamp, and
286 * targets used to create the estimate.
287 */
288 std::optional<EstimatedRobotPose> Update(const PhotonPipelineResult& result,
289 PoseStrategy strategy) {
290 return Update(result, std::nullopt, std::nullopt, std::nullopt, strategy);
291 }
292
293 std::optional<EstimatedRobotPose> Update(
294 const PhotonPipelineResult& result,
295 std::optional<PhotonCamera::CameraMatrix> cameraMatrixData,
296 std::optional<PhotonCamera::DistortionMatrix> coeffsData,
297 std::optional<ConstrainedSolvepnpParams> constrainedPnpParams,
298 PoseStrategy strategy);
299
300 /**
301 * Return the estimated position of the robot with the lowest position
302 * ambiguity from a List of pipeline results.
303 *
304 * @return the estimated position of the robot in the FCS and the estimated
305 * timestamp of this estimation.
306 */
307 std::optional<EstimatedRobotPose> LowestAmbiguityStrategy(
308 PhotonPipelineResult result);
309
310 /**
311 * Return the estimated position of the robot using the target with the lowest
312 * delta height difference between the estimated and actual height of the
313 * camera.
314 *
315 * @return the estimated position of the robot in the FCS and the estimated
316 * timestamp of this estimation.
317 */
318 std::optional<EstimatedRobotPose> ClosestToCameraHeightStrategy(
319 PhotonPipelineResult result);
320
321 /**
322 * Return the estimated position of the robot using the target with the lowest
323 * delta in the vector magnitude between it and the reference pose.
324 *
325 * @param referencePose reference pose to check vector magnitude difference
326 * against.
327 * @return the estimated position of the robot in the FCS and the estimated
328 * timestamp of this estimation.
329 */
330 std::optional<EstimatedRobotPose> ClosestToReferencePoseStrategy(
331 PhotonPipelineResult result);
332
333 /**
334 * Return the pose calculated by combining all tags into one on coprocessor
335 *
336 * @return the estimated position of the robot in the FCS
337 */
338 std::optional<EstimatedRobotPose> MultiTagOnCoprocStrategy(
339 PhotonPipelineResult result);
340
341 /**
342 * Return the pose calculation using all targets in view in the same PNP()
343 calculation
344 *
345 * @return the estimated position of the robot in the FCS and the estimated
346 timestamp of this estimation.
347 */
348 std::optional<EstimatedRobotPose> MultiTagOnRioStrategy(
349 PhotonPipelineResult result,
350 std::optional<PhotonCamera::CameraMatrix> camMat,
351 std::optional<PhotonCamera::DistortionMatrix> distCoeffs);
352
353 /**
354 * Return the pose calculation using the best visible tag and the robot's
355 * heading
356 *
357 * @return the estimated position of the robot in the FCS and the estimated
358 * timestamp of this estimation
359 */
360 std::optional<EstimatedRobotPose> PnpDistanceTrigSolveStrategy(
361 PhotonPipelineResult result);
362
363 /**
364 * Return the average of the best target poses using ambiguity as weight.
365
366 * @return the estimated position of the robot in the FCS and the estimated
367 timestamp of this estimation.
368 */
369 std::optional<EstimatedRobotPose> AverageBestTargetsStrategy(
370 PhotonPipelineResult result);
371
372 std::optional<EstimatedRobotPose> ConstrainedPnpStrategy(
374 std::optional<photon::PhotonCamera::CameraMatrix> camMat,
375 std::optional<photon::PhotonCamera::DistortionMatrix> distCoeffs,
376 std::optional<ConstrainedSolvepnpParams> constrainedPnpParams);
377};
378
379} // namespace photon
Represents a pipeline result from a PhotonCamera.
Definition PhotonPipelineResult.h:37
The PhotonPoseEstimator class filters or combines readings from all the fiducials visible at a given ...
Definition PhotonPoseEstimator.h:89
frc::Transform3d GetRobotToCameraTransform()
Definition PhotonPoseEstimator.h:162
PhotonPoseEstimator(frc::AprilTagFieldLayout aprilTags, PoseStrategy strategy, frc::Transform3d robotToCamera)
Create a new PhotonPoseEstimator.
void AddHeadingData(units::second_t timestamp, frc::Rotation3d heading)
Add robot heading data to the buffer.
Definition PhotonPoseEstimator.h:205
void SetReferencePose(frc::Pose3d referencePose)
Update the stored reference pose for use when using the CLOSEST_TO_REFERENCE_POSE strategy.
Definition PhotonPoseEstimator.h:151
frc::AprilTagFieldLayout GetFieldLayout() const
Get the AprilTagFieldLayout being used by the PositionEstimator.
Definition PhotonPoseEstimator.h:109
void ResetHeadingData(units::second_t timestamp, frc::Rotation2d heading)
Clears all heading data in the buffer, and adds a new seed.
Definition PhotonPoseEstimator.h:219
PoseStrategy GetPoseStrategy() const
Get the Position Estimation Strategy being used by the Position Estimator.
Definition PhotonPoseEstimator.h:116
void AddHeadingData(units::second_t timestamp, frc::Rotation2d heading)
Add robot heading data to the buffer.
Definition PhotonPoseEstimator.h:192
void ResetHeadingData(units::second_t timestamp, frc::Rotation3d heading)
Clears all heading data in the buffer, and adds a new seed.
Definition PhotonPoseEstimator.h:234
std::optional< EstimatedRobotPose > Update(const photon::PhotonPipelineResult &result, std::optional< photon::PhotonCamera::CameraMatrix > cameraMatrixData=std::nullopt, std::optional< photon::PhotonCamera::DistortionMatrix > coeffsData=std::nullopt, std::optional< ConstrainedSolvepnpParams > constrainedPnpParams=std::nullopt)
Update the pose estimator.
void SetRobotToCameraTransform(frc::Transform3d robotToCamera)
Useful for pan and tilt mechanisms, or cameras on turrets.
Definition PhotonPoseEstimator.h:172
void SetMultiTagFallbackStrategy(PoseStrategy strategy)
Set the Position Estimation Strategy used in multi-tag mode when only one tag can be seen.
frc::Pose3d GetReferencePose() const
Return the reference position that is being used by the estimator.
Definition PhotonPoseEstimator.h:143
void SetLastPose(frc::Pose3d lastPose)
Update the stored last pose.
Definition PhotonPoseEstimator.h:182
void SetPoseStrategy(PoseStrategy strat)
Set the Position Estimation Strategy used by the Position Estimator.
Definition PhotonPoseEstimator.h:123
Definition VisionEstimation.h:30
PoseStrategy
Definition PhotonPoseEstimator.h:44
@ CONSTRAINED_SOLVEPNP
Definition PhotonPoseEstimator.h:52
@ LOWEST_AMBIGUITY
Definition PhotonPoseEstimator.h:45
@ AVERAGE_BEST_TARGETS
Definition PhotonPoseEstimator.h:49
@ PNP_DISTANCE_TRIG_SOLVE
Definition PhotonPoseEstimator.h:53
@ MULTI_TAG_PNP_ON_RIO
Definition PhotonPoseEstimator.h:51
@ CLOSEST_TO_CAMERA_HEIGHT
Definition PhotonPoseEstimator.h:46
@ CLOSEST_TO_LAST_POSE
Definition PhotonPoseEstimator.h:48
@ MULTI_TAG_PNP_ON_COPROCESSOR
Definition PhotonPoseEstimator.h:50
@ CLOSEST_TO_REFERENCE_POSE
Definition PhotonPoseEstimator.h:47
Definition PhotonPoseEstimator.h:56
bool headingFree
Definition PhotonPoseEstimator.h:57
double headingScalingFactor
Definition PhotonPoseEstimator.h:58
Definition PhotonPoseEstimator.h:61
EstimatedRobotPose(frc::Pose3d pose_, units::second_t time_, std::span< const PhotonTrackedTarget > targets, PoseStrategy strategy_)
Definition PhotonPoseEstimator.h:74
wpi::SmallVector< PhotonTrackedTarget, 10 > targetsUsed
A list of the targets used to compute this pose.
Definition PhotonPoseEstimator.h:69
frc::Pose3d estimatedPose
The estimated pose.
Definition PhotonPoseEstimator.h:63
PoseStrategy strategy
The strategy actually used to produce this pose.
Definition PhotonPoseEstimator.h:72
units::second_t timestamp
The estimated time the frame used to derive the robot pose was taken, in the same timebase as the Rob...
Definition PhotonPoseEstimator.h:66