PhotonVision C++ v2026.2.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 <frc/apriltag/AprilTagFieldLayout.h>
28#include <frc/geometry/Pose3d.h>
29#include <frc/geometry/Rotation3d.h>
30#include <frc/geometry/Transform3d.h>
31#include <frc/interpolation/TimeInterpolatableBuffer.h>
32#include <opencv2/core/mat.hpp>
33
34#include "photon/PhotonCamera.h"
37
38namespace photon {
50
55
57 /** The estimated pose */
58 frc::Pose3d estimatedPose;
59 /** The estimated time the frame used to derive the robot pose was taken, in
60 * the same timebase as the RoboRIO FPGA Timestamp */
61 units::second_t timestamp;
62
63 /** A list of the targets used to compute this pose */
64 wpi::SmallVector<PhotonTrackedTarget, 10> targetsUsed;
65
66 /** The strategy actually used to produce this pose */
68
69 EstimatedRobotPose(frc::Pose3d pose_, units::second_t time_,
70 std::span<const PhotonTrackedTarget> targets,
71 PoseStrategy strategy_)
72 : estimatedPose(pose_),
73 timestamp(time_),
74 targetsUsed(targets.data(), targets.data() + targets.size()),
75 strategy(strategy_) {}
76};
77
78/**
79 * The PhotonPoseEstimator class filters or combines readings from all the
80 * fiducials visible at a given timestamp on the field to produce a single robot
81 * in field pose, using the strategy set below. Example usage can be found in
82 * our apriltagExample example project.
83 */
85 public:
86 /**
87 * Create a new PhotonPoseEstimator.
88 *
89 * @param aprilTags A AprilTagFieldLayout linking AprilTag IDs to Pose3ds with
90 * respect to the FIRST field.
91 * @param robotToCamera Transform3d from the center of the robot to the camera
92 * mount positions (ie, robot ➔ camera).
93 */
94 explicit PhotonPoseEstimator(frc::AprilTagFieldLayout aprilTags,
95 frc::Transform3d robotToCamera);
96
97 /**
98 * Create a new PhotonPoseEstimator.
99 *
100 * @param aprilTags A AprilTagFieldLayout linking AprilTag IDs to Pose3ds with
101 * respect to the FIRST field.
102 * @param strategy The strategy it should use to determine the best pose.
103 * @param robotToCamera Transform3d from the center of the robot to the camera
104 * mount positions (ie, robot ➔ camera).
105 * @deprecated Use individual estimation methods with the 2 argument
106 * constructor instead.
107 */
108 [[deprecated(
109 "Use individual estimation methods with the 2 argument constructor "
110 "instead.")]]
111 explicit PhotonPoseEstimator(frc::AprilTagFieldLayout aprilTags,
112 PoseStrategy strategy,
113 frc::Transform3d robotToCamera);
114
115 /**
116 * Get the AprilTagFieldLayout being used by the PositionEstimator.
117 *
118 * @return the AprilTagFieldLayout
119 */
120 frc::AprilTagFieldLayout GetFieldLayout() const { return aprilTags; }
121
122 /**
123 * Get the Position Estimation Strategy being used by the Position Estimator.
124 *
125 * @return the strategy
126 * @deprecated Use individual estimation methods instead.
127 */
128 [[deprecated("Use individual estimation methods instead.")]]
130 return strategy;
131 }
132
133 /**
134 * Set the Position Estimation Strategy used by the Position Estimator.
135 *
136 * @param strategy the strategy to set
137 * @deprecated Use individual estimation methods instead.
138 */
139 [[deprecated("Use individual estimation methods instead.")]]
140 inline void SetPoseStrategy(PoseStrategy strat) {
141 if (strategy != strat) {
142 InvalidatePoseCache();
143 }
144 strategy = strat;
145 }
146
147 /**
148 * Set the Position Estimation Strategy used in multi-tag mode when
149 * only one tag can be seen. Must NOT be MULTI_TAG_PNP
150 *
151 * @param strategy the strategy to set
152 * @deprecated Use individual estimation methods instead.
153 */
154 [[deprecated("Use individual estimation methods instead.")]]
156
157 /**
158 * Return the reference position that is being used by the estimator.
159 *
160 * @return the referencePose
161 * @deprecated Use individual estimation methods instead.
162 */
163 [[deprecated("Use individual estimation methods instead.")]]
164 frc::Pose3d GetReferencePose() const {
165 return referencePose;
166 }
167
168 /**
169 * Update the stored reference pose for use when using the
170 * CLOSEST_TO_REFERENCE_POSE strategy.
171 *
172 * @param referencePose the referencePose to set
173 * @deprecated Use individual estimation methods instead.
174 */
175 [[deprecated("Use individual estimation methods instead.")]]
176 inline void SetReferencePose(frc::Pose3d referencePose) {
177 if (this->referencePose != referencePose) {
178 InvalidatePoseCache();
179 }
180 this->referencePose = referencePose;
181 }
182
183 /**
184 * @return The current transform from the center of the robot to the camera
185 * mount position.
186 */
187 inline frc::Transform3d GetRobotToCameraTransform() {
188 return m_robotToCamera;
189 }
190
191 /**
192 * Useful for pan and tilt mechanisms, or cameras on turrets
193 *
194 * @param robotToCamera The current transform from the center of the robot to
195 * the camera mount position.
196 */
197 inline void SetRobotToCameraTransform(frc::Transform3d robotToCamera) {
198 m_robotToCamera = robotToCamera;
199 }
200
201 /**
202 * Update the stored last pose. Useful for setting the initial estimate when
203 * using the CLOSEST_TO_LAST_POSE strategy.
204 *
205 * @param lastPose the lastPose to set
206 * @deprecated Use individual estimation methods instead.
207 */
208 [[deprecated("Use individual estimation methods instead.")]]
209 inline void SetLastPose(frc::Pose3d lastPose) {
210 this->lastPose = lastPose;
211 }
212
213 /**
214 * Add robot heading data to the buffer. Must be called periodically for the
215 * PNP_DISTANCE_TRIG_SOLVE strategy.
216 *
217 * @param timestamp Timestamp of the robot heading data.
218 * @param heading Field-relative heading at the given timestamp. Standard
219 * WPILIB field coordinates.
220 */
221 inline void AddHeadingData(units::second_t timestamp,
222 frc::Rotation2d heading) {
223 this->headingBuffer.AddSample(timestamp, heading);
224 }
225
226 /**
227 * Add robot heading data to the buffer. Must be called periodically for the
228 * PNP_DISTANCE_TRIG_SOLVE strategy.
229 *
230 * @param timestamp Timestamp of the robot heading data.
231 * @param heading Field-relative heading at the given timestamp. Standard
232 * WPILIB coordinates.
233 */
234 inline void AddHeadingData(units::second_t timestamp,
235 frc::Rotation3d heading) {
236 AddHeadingData(timestamp, heading.ToRotation2d());
237 }
238
239 /**
240 * Clears all heading data in the buffer, and adds a new seed. Useful for
241 * preventing estimates from utilizing heading data provided prior to a pose
242 * or rotation reset.
243 *
244 * @param timestamp Timestamp of the robot heading data.
245 * @param heading Field-relative robot heading at given timestamp. Standard
246 * WPILIB field coordinates.
247 */
248 inline void ResetHeadingData(units::second_t timestamp,
249 frc::Rotation2d heading) {
250 headingBuffer.Clear();
251 AddHeadingData(timestamp, heading);
252 }
253
254 /**
255 * Clears all heading data in the buffer, and adds a new seed. Useful for
256 * preventing estimates from utilizing heading data provided prior to a pose
257 * or rotation reset.
258 *
259 * @param timestamp Timestamp of the robot heading data.
260 * @param heading Field-relative robot heading at given timestamp. Standard
261 * WPILIB field coordinates.
262 */
263 inline void ResetHeadingData(units::second_t timestamp,
264 frc::Rotation3d heading) {
265 ResetHeadingData(timestamp, heading.ToRotation2d());
266 }
267
268 /**
269 * Update the pose estimator. If updating multiple times per loop, you should
270 * call this exactly once per new result, in order of increasing result
271 * timestamp.
272 *
273 * @param result The vision targeting result to process
274 * @param cameraIntrinsics The camera calibration pinhole coefficients matrix.
275 * Only required if doing multitag-on-rio, and may be nullopt otherwise.
276 * @param distCoeffsData The camera calibration distortion coefficients. Only
277 * required if doing multitag-on-rio, and may be nullopt otherwise.
278 * @param constrainedPnpParams Constrained SolvePNP params, if needed.
279 * @deprecated Use individual estimation methods instead.
280 */
281 [[deprecated("Use individual estimation methods instead.")]]
282 std::optional<EstimatedRobotPose> Update(
283 const photon::PhotonPipelineResult& result,
284 std::optional<photon::PhotonCamera::CameraMatrix> cameraMatrixData =
285 std::nullopt,
286 std::optional<photon::PhotonCamera::DistortionMatrix> coeffsData =
287 std::nullopt,
288 std::optional<ConstrainedSolvepnpParams> constrainedPnpParams =
289 std::nullopt);
290
291 /**
292 * Return the estimated position of the robot with the lowest position
293 * ambiguity from a List of pipeline results.
294 *
295 * @param cameraResult A pipeline result from the camera.
296 * @return An EstimatedRobotPose with an estimated pose, timestamp, and
297 * targets used to create the estimate, or std::nullopt if there's no targets.
298 */
299 std::optional<EstimatedRobotPose> EstimateLowestAmbiguityPose(
300 PhotonPipelineResult cameraResult);
301
302 /**
303 * Return the estimated position of the robot using the target with the lowest
304 * delta height difference between the estimated and actual height of the
305 * camera.
306 *
307 * @param cameraResult A pipeline result from the camera.
308 * @return An EstimatedRobotPose with an estimated pose, timestamp and
309 * targets used to create the estimate, or std::nullopt if there's no targets.
310 */
311 std::optional<EstimatedRobotPose> EstimateClosestToCameraHeightPose(
312 PhotonPipelineResult cameraResult);
313
314 /**
315 * Return the estimated position of the robot using the target with the lowest
316 * delta in the vector magnitude between it and the reference pose.
317 *
318 * @param cameraResult A pipeline result from the camera.
319 * @param referencePose reference pose to check vector magnitude difference
320 * against.
321 * @return An EstimatedRobotPose with an estimated pose, timestamp, and
322 * targets used to create the estimate, or std::nullopt if there's no targets.
323 */
324 std::optional<EstimatedRobotPose> EstimateClosestToReferencePose(
325 PhotonPipelineResult cameraResult, frc::Pose3d referencePose);
326
327 /**
328 * Return the estimated position of the robot by using all visible tags to
329 * compute a single pose estimate on coprocessor. This option needs to be
330 * enabled on the PhotonVision web UI as well.
331 *
332 * @param cameraResult A pipeline result from the camera.
333 * @return An EstimatedRobotPose with an estimated pose, timestamp, and
334 * targets used to create the estimate or std::nullopt if there's no targets,
335 * no multi-tag results, or multi-tag is disabled in the web UI.
336 */
337 std::optional<EstimatedRobotPose> EstimateCoprocMultiTagPose(
338 PhotonPipelineResult cameraResult);
339
340 /**
341 * Return the estimated position of the robot by using all visible tags to
342 * compute a single pose estimate on the RoboRIO. This can take a lot of time
343 * due to the RIO's weak computing power.
344 *
345 * @param cameraResult A pipeline result from the camera.
346 * @param cameraMatrix Camera intrinsics from camera calibration data.
347 * @param distCoeffs Distortion coefficients from camera calibration data.
348 * @return An EstimatedRobotPose with an estimated pose, timestamp, and
349 * targets used to create the estimate, or std::nullopt if there's less than 2
350 * targets visible or SolvePnP fails.
351 */
352 std::optional<EstimatedRobotPose> EstimateRioMultiTagPose(
355
356 /**
357 * Return the estimated position of the robot by using distance data from best
358 * visible tag to compute a Pose. This runs on the RoboRIO in order to access
359 * the robot's yaw heading, and MUST have AddHeadingData called every frame so
360 * heading data is up-to-date.
361 *
362 * <p>Yields a Pose2d in estimatedRobotPose (0 for z, roll, pitch)
363 *
364 * <p>https://www.chiefdelphi.com/t/frc-6328-mechanical-advantage-2025-build-thread/477314/98
365 *
366 * @param cameraResult A pipeline result from the camera.
367 * @return An EstimatedRobotPose with an estimated pose, timestamp, and
368 * targets used to create the estimate, or std::nullopt if there's no targets
369 * or heading data.
370 */
371 std::optional<EstimatedRobotPose> EstimatePnpDistanceTrigSolvePose(
372 PhotonPipelineResult cameraResult);
373
374 /**
375 * Return the average of the best target poses using ambiguity as weight.
376 * @param cameraResult A pipeline result from the camera.
377 * @return An EstimatedRobotPose with an estimated pose, timestamp, and
378 * targets used to create the estimate, or std::nullopt if there's no targets.
379 */
380 std::optional<EstimatedRobotPose> EstimateAverageBestTargetsPose(
381 PhotonPipelineResult cameraResult);
382
383 /**
384 * Return the estimated position of the robot by solving a constrained version
385 * of the Perspective-n-Point problem with the robot's drivebase flat on the
386 * floor. This computation takes place on the RoboRIO, and typically takes not
387 * more than 2ms. See
388 * photon::VisionEstimation::EstimateRobotPoseConstrainedSolvePNP for tuning
389 * handles this strategy exposes. Internally, the cost function is a
390 * sum-squared of pixel reprojection error + (optionally) heading error *
391 * heading scale factor. This strategy needs addHeadingData called every frame
392 * so heading data is up-to-date.
393 *
394 * @param cameraResult A pipeline result from the camera.
395 * @param cameraMatrix Camera intrinsics from camera calibration data.
396 * @param distCoeffs Distortion coefficients from camera calibration data.
397 * @param seedPose An initial guess at robot pose, refined via optimization.
398 * Better guesses will converge faster. Can come from any pose source, but
399 * some battle-tested sources are estimateCoprocMultiTagPose, or
400 * estimateLowestAmbiguityPose if MultiTag results aren't available.
401 * @param headingFree If true, heading is completely free to vary. If false,
402 * heading excursions from the provided heading measurement will be penalized
403 * @param headingScaleFactor If headingFree is false, this weights the cost of
404 * changing our robot heading estimate against the tag corner reprojection
405 * error cost.
406 * @return An EstimatedRobotPose with an estimated pose, timestamp, and
407 * targets used to create the estimate, or std::nullopt if there's no targets
408 * or heading data, or if the solver fails to solve the problem.
409 */
410 std::optional<EstimatedRobotPose> EstimateConstrainedSolvepnpPose(
411 photon::PhotonPipelineResult cameraResult,
413 photon::PhotonCamera::DistortionMatrix distCoeffs, frc::Pose3d seedPose,
414 bool headingFree, double headingScaleFactor);
415
416 private:
417 frc::AprilTagFieldLayout aprilTags;
418 PoseStrategy strategy;
419 PoseStrategy multiTagFallbackStrategy = LOWEST_AMBIGUITY;
420
421 frc::Transform3d m_robotToCamera;
422
423 frc::Pose3d lastPose;
424 frc::Pose3d referencePose;
425
426 units::second_t poseCacheTimestamp;
427
428 frc::TimeInterpolatableBuffer<frc::Rotation2d> headingBuffer;
429
430 inline static int InstanceCount = 1;
431
432 inline void InvalidatePoseCache() { poseCacheTimestamp = -1_s; }
433
434 /**
435 * Internal convenience method for using a fallback strategy for update().
436 * This should only be called after timestamp checks have been done by another
437 * update() overload.
438 *
439 * @param cameraResult A pipeline result from the camera.
440 * @param strategy The pose strategy to use
441 * @return An EstimatedRobotPose with an estimated pose, timestamp, and
442 * targets used to create the estimate.
443 */
444 std::optional<EstimatedRobotPose> Update(const PhotonPipelineResult& result,
445 PoseStrategy strategy) {
446 return Update(result, std::nullopt, std::nullopt, std::nullopt, strategy);
447 }
448
449 std::optional<EstimatedRobotPose> Update(
450 const PhotonPipelineResult& result,
451 std::optional<PhotonCamera::CameraMatrix> cameraMatrixData,
452 std::optional<PhotonCamera::DistortionMatrix> coeffsData,
453 std::optional<ConstrainedSolvepnpParams> constrainedPnpParams,
454 PoseStrategy strategy);
455};
456
457} // namespace photon
Eigen::Matrix< double, 8, 1 > DistortionMatrix
Definition PhotonCamera.h:179
Eigen::Matrix< double, 3, 3 > CameraMatrix
Definition PhotonCamera.h:178
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:84
std::optional< EstimatedRobotPose > EstimateAverageBestTargetsPose(PhotonPipelineResult cameraResult)
Return the average of the best target poses using ambiguity as weight.
frc::Transform3d GetRobotToCameraTransform()
Definition PhotonPoseEstimator.h:187
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:234
void SetReferencePose(frc::Pose3d referencePose)
Update the stored reference pose for use when using the CLOSEST_TO_REFERENCE_POSE strategy.
Definition PhotonPoseEstimator.h:176
frc::AprilTagFieldLayout GetFieldLayout() const
Get the AprilTagFieldLayout being used by the PositionEstimator.
Definition PhotonPoseEstimator.h:120
std::optional< EstimatedRobotPose > EstimateClosestToCameraHeightPose(PhotonPipelineResult cameraResult)
Return the estimated position of the robot using the target with the lowest delta height difference b...
void ResetHeadingData(units::second_t timestamp, frc::Rotation2d heading)
Clears all heading data in the buffer, and adds a new seed.
Definition PhotonPoseEstimator.h:248
PhotonPoseEstimator(frc::AprilTagFieldLayout aprilTags, frc::Transform3d robotToCamera)
Create a new PhotonPoseEstimator.
std::optional< EstimatedRobotPose > EstimateLowestAmbiguityPose(PhotonPipelineResult cameraResult)
Return the estimated position of the robot with the lowest position ambiguity from a List of pipeline...
PoseStrategy GetPoseStrategy() const
Get the Position Estimation Strategy being used by the Position Estimator.
Definition PhotonPoseEstimator.h:129
std::optional< EstimatedRobotPose > EstimateCoprocMultiTagPose(PhotonPipelineResult cameraResult)
Return the estimated position of the robot by using all visible tags to compute a single pose estimat...
void AddHeadingData(units::second_t timestamp, frc::Rotation2d heading)
Add robot heading data to the buffer.
Definition PhotonPoseEstimator.h:221
std::optional< EstimatedRobotPose > EstimatePnpDistanceTrigSolvePose(PhotonPipelineResult cameraResult)
Return the estimated position of the robot by using distance data from best visible tag to compute a ...
void ResetHeadingData(units::second_t timestamp, frc::Rotation3d heading)
Clears all heading data in the buffer, and adds a new seed.
Definition PhotonPoseEstimator.h:263
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.
std::optional< EstimatedRobotPose > EstimateRioMultiTagPose(PhotonPipelineResult cameraResult, PhotonCamera::CameraMatrix camMat, PhotonCamera::DistortionMatrix distCoeffs)
Return the estimated position of the robot by using all visible tags to compute a single pose estimat...
void SetRobotToCameraTransform(frc::Transform3d robotToCamera)
Useful for pan and tilt mechanisms, or cameras on turrets.
Definition PhotonPoseEstimator.h:197
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:164
std::optional< EstimatedRobotPose > EstimateConstrainedSolvepnpPose(photon::PhotonPipelineResult cameraResult, photon::PhotonCamera::CameraMatrix cameraMatrix, photon::PhotonCamera::DistortionMatrix distCoeffs, frc::Pose3d seedPose, bool headingFree, double headingScaleFactor)
Return the estimated position of the robot by solving a constrained version of the Perspective-n-Poin...
void SetLastPose(frc::Pose3d lastPose)
Update the stored last pose.
Definition PhotonPoseEstimator.h:209
void SetPoseStrategy(PoseStrategy strat)
Set the Position Estimation Strategy used by the Position Estimator.
Definition PhotonPoseEstimator.h:140
std::optional< EstimatedRobotPose > EstimateClosestToReferencePose(PhotonPipelineResult cameraResult, frc::Pose3d referencePose)
Return the estimated position of the robot using the target with the lowest delta in the vector magni...
Definition TargetModel.h:27
PoseStrategy
Definition PhotonPoseEstimator.h:39
@ CONSTRAINED_SOLVEPNP
Definition PhotonPoseEstimator.h:47
@ LOWEST_AMBIGUITY
Definition PhotonPoseEstimator.h:40
@ AVERAGE_BEST_TARGETS
Definition PhotonPoseEstimator.h:44
@ PNP_DISTANCE_TRIG_SOLVE
Definition PhotonPoseEstimator.h:48
@ MULTI_TAG_PNP_ON_RIO
Definition PhotonPoseEstimator.h:46
@ CLOSEST_TO_CAMERA_HEIGHT
Definition PhotonPoseEstimator.h:41
@ CLOSEST_TO_LAST_POSE
Definition PhotonPoseEstimator.h:43
@ MULTI_TAG_PNP_ON_COPROCESSOR
Definition PhotonPoseEstimator.h:45
@ CLOSEST_TO_REFERENCE_POSE
Definition PhotonPoseEstimator.h:42
Definition PhotonPoseEstimator.h:51
bool headingFree
Definition PhotonPoseEstimator.h:52
double headingScalingFactor
Definition PhotonPoseEstimator.h:53
Definition PhotonPoseEstimator.h:56
EstimatedRobotPose(frc::Pose3d pose_, units::second_t time_, std::span< const PhotonTrackedTarget > targets, PoseStrategy strategy_)
Definition PhotonPoseEstimator.h:69
wpi::SmallVector< PhotonTrackedTarget, 10 > targetsUsed
A list of the targets used to compute this pose.
Definition PhotonPoseEstimator.h:64
frc::Pose3d estimatedPose
The estimated pose.
Definition PhotonPoseEstimator.h:58
PoseStrategy strategy
The strategy actually used to produce this pose.
Definition PhotonPoseEstimator.h:67
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:61