PhotonVision C++ dev-v2025.3.1-2-gf92cf62a
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/Transform3d.h>
32#include <opencv2/core/mat.hpp>
33
34#include "photon/PhotonCamera.h"
40
41namespace photon {
51
53 /** The estimated pose */
54 frc::Pose3d estimatedPose;
55 /** The estimated time the frame used to derive the robot pose was taken, in
56 * the same timebase as the RoboRIO FPGA Timestamp */
57 units::second_t timestamp;
58
59 /** A list of the targets used to compute this pose */
60 wpi::SmallVector<PhotonTrackedTarget, 10> targetsUsed;
61
62 /** The strategy actually used to produce this pose */
64
65 EstimatedRobotPose(frc::Pose3d pose_, units::second_t time_,
66 std::span<const PhotonTrackedTarget> targets,
67 PoseStrategy strategy_)
68 : estimatedPose(pose_),
69 timestamp(time_),
70 targetsUsed(targets.data(), targets.data() + targets.size()),
71 strategy(strategy_) {}
72};
73
74/**
75 * The PhotonPoseEstimator class filters or combines readings from all the
76 * fiducials visible at a given timestamp on the field to produce a single robot
77 * in field pose, using the strategy set below. Example usage can be found in
78 * our apriltagExample example project.
79 */
81 public:
82 /**
83 * Create a new PhotonPoseEstimator.
84 *
85 * @param aprilTags A AprilTagFieldLayout linking AprilTag IDs to Pose3ds with
86 * respect to the FIRST field.
87 * @param strategy The strategy it should use to determine the best pose.
88 * @param robotToCamera Transform3d from the center of the robot to the camera
89 * mount positions (ie, robot ➔ camera).
90 */
91 explicit PhotonPoseEstimator(frc::AprilTagFieldLayout aprilTags,
92 PoseStrategy strategy,
93 frc::Transform3d robotToCamera);
94
95 /**
96 * Get the AprilTagFieldLayout being used by the PositionEstimator.
97 *
98 * @return the AprilTagFieldLayout
99 */
100 frc::AprilTagFieldLayout GetFieldLayout() const { return aprilTags; }
101
102 /**
103 * Get the Position Estimation Strategy being used by the Position Estimator.
104 *
105 * @return the strategy
106 */
107 PoseStrategy GetPoseStrategy() const { return strategy; }
108
109 /**
110 * Set the Position Estimation Strategy used by the Position Estimator.
111 *
112 * @param strategy the strategy to set
113 */
114 inline void SetPoseStrategy(PoseStrategy strat) {
115 if (strategy != strat) {
116 InvalidatePoseCache();
117 }
118 strategy = strat;
119 }
120
121 /**
122 * Set the Position Estimation Strategy used in multi-tag mode when
123 * only one tag can be seen. Must NOT be MULTI_TAG_PNP
124 *
125 * @param strategy the strategy to set
126 */
128
129 /**
130 * Return the reference position that is being used by the estimator.
131 *
132 * @return the referencePose
133 */
134 frc::Pose3d GetReferencePose() const { return referencePose; }
135
136 /**
137 * Update the stored reference pose for use when using the
138 * CLOSEST_TO_REFERENCE_POSE strategy.
139 *
140 * @param referencePose the referencePose to set
141 */
142 inline void SetReferencePose(frc::Pose3d referencePose) {
143 if (this->referencePose != referencePose) {
144 InvalidatePoseCache();
145 }
146 this->referencePose = referencePose;
147 }
148
149 /**
150 * @return The current transform from the center of the robot to the camera
151 * mount position.
152 */
153 inline frc::Transform3d GetRobotToCameraTransform() {
154 return m_robotToCamera;
155 }
156
157 /**
158 * Useful for pan and tilt mechanisms, or cameras on turrets
159 *
160 * @param robotToCamera The current transform from the center of the robot to
161 * the camera mount position.
162 */
163 inline void SetRobotToCameraTransform(frc::Transform3d robotToCamera) {
164 m_robotToCamera = robotToCamera;
165 }
166
167 /**
168 * Update the stored last pose. Useful for setting the initial estimate when
169 * using the CLOSEST_TO_LAST_POSE strategy.
170 *
171 * @param lastPose the lastPose to set
172 */
173 inline void SetLastPose(frc::Pose3d lastPose) { this->lastPose = lastPose; }
174
175 /**
176 * Update the pose estimator. If updating multiple times per loop, you should
177 * call this exactly once per new result, in order of increasing result
178 * timestamp.
179 *
180 * @param result The vision targeting result to process
181 * @param cameraIntrinsics The camera calibration pinhole coefficients matrix.
182 * Only required if doing multitag-on-rio, and may be nullopt otherwise.
183 * @param distCoeffsData The camera calibration distortion coefficients. Only
184 * required if doing multitag-on-rio, and may be nullopt otherwise.
185 */
186 std::optional<EstimatedRobotPose> Update(
187 const PhotonPipelineResult& result,
188 std::optional<PhotonCamera::CameraMatrix> cameraMatrixData = std::nullopt,
189 std::optional<PhotonCamera::DistortionMatrix> coeffsData = std::nullopt);
190
191 private:
192 frc::AprilTagFieldLayout aprilTags;
193 PoseStrategy strategy;
194 PoseStrategy multiTagFallbackStrategy = LOWEST_AMBIGUITY;
195
196 frc::Transform3d m_robotToCamera;
197
198 frc::Pose3d lastPose;
199 frc::Pose3d referencePose;
200
201 units::second_t poseCacheTimestamp;
202
203 inline static int InstanceCount = 0;
204
205 inline void InvalidatePoseCache() { poseCacheTimestamp = -1_s; }
206
207 /**
208 * Internal convenience method for using a fallback strategy for update().
209 * This should only be called after timestamp checks have been done by another
210 * update() overload.
211 *
212 * @param cameraResult The latest pipeline result from the camera
213 * @param strategy The pose strategy to use
214 * @return an EstimatedRobotPose with an estimated pose, timestamp, and
215 * targets used to create the estimate.
216 */
217 std::optional<EstimatedRobotPose> Update(const PhotonPipelineResult& result,
218 PoseStrategy strategy) {
219 return Update(result, std::nullopt, std::nullopt, strategy);
220 }
221
222 std::optional<EstimatedRobotPose> Update(
223 const PhotonPipelineResult& result,
224 std::optional<PhotonCamera::CameraMatrix> cameraMatrixData,
225 std::optional<PhotonCamera::DistortionMatrix> coeffsData,
226 PoseStrategy strategy);
227
228 /**
229 * Return the estimated position of the robot with the lowest position
230 * ambiguity from a List of pipeline results.
231 *
232 * @return the estimated position of the robot in the FCS and the estimated
233 * timestamp of this estimation.
234 */
235 std::optional<EstimatedRobotPose> LowestAmbiguityStrategy(
236 PhotonPipelineResult result);
237
238 /**
239 * Return the estimated position of the robot using the target with the lowest
240 * delta height difference between the estimated and actual height of the
241 * camera.
242 *
243 * @return the estimated position of the robot in the FCS and the estimated
244 * timestamp of this estimation.
245 */
246 std::optional<EstimatedRobotPose> ClosestToCameraHeightStrategy(
247 PhotonPipelineResult result);
248
249 /**
250 * Return the estimated position of the robot using the target with the lowest
251 * delta in the vector magnitude between it and the reference pose.
252 *
253 * @param referencePose reference pose to check vector magnitude difference
254 * against.
255 * @return the estimated position of the robot in the FCS and the estimated
256 * timestamp of this estimation.
257 */
258 std::optional<EstimatedRobotPose> ClosestToReferencePoseStrategy(
259 PhotonPipelineResult result);
260
261 /**
262 * Return the pose calculated by combining all tags into one on coprocessor
263 *
264 * @return the estimated position of the robot in the FCS
265 */
266 std::optional<EstimatedRobotPose> MultiTagOnCoprocStrategy(
267 PhotonPipelineResult result);
268
269 /**
270 * Return the pose calculation using all targets in view in the same PNP()
271 calculation
272 *
273 * @return the estimated position of the robot in the FCS and the estimated
274 timestamp of this estimation.
275 */
276 std::optional<EstimatedRobotPose> MultiTagOnRioStrategy(
277 PhotonPipelineResult result,
278 std::optional<PhotonCamera::CameraMatrix> camMat,
279 std::optional<PhotonCamera::DistortionMatrix> distCoeffs);
280
281 /**
282 * Return the average of the best target poses using ambiguity as weight.
283
284 * @return the estimated position of the robot in the FCS and the estimated
285 timestamp of this estimation.
286 */
287 std::optional<EstimatedRobotPose> AverageBestTargetsStrategy(
288 PhotonPipelineResult result);
289};
290
291} // 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:80
frc::Transform3d GetRobotToCameraTransform()
Definition PhotonPoseEstimator.h:153
PhotonPoseEstimator(frc::AprilTagFieldLayout aprilTags, PoseStrategy strategy, frc::Transform3d robotToCamera)
Create a new PhotonPoseEstimator.
void SetReferencePose(frc::Pose3d referencePose)
Update the stored reference pose for use when using the CLOSEST_TO_REFERENCE_POSE strategy.
Definition PhotonPoseEstimator.h:142
frc::AprilTagFieldLayout GetFieldLayout() const
Get the AprilTagFieldLayout being used by the PositionEstimator.
Definition PhotonPoseEstimator.h:100
PoseStrategy GetPoseStrategy() const
Get the Position Estimation Strategy being used by the Position Estimator.
Definition PhotonPoseEstimator.h:107
void SetRobotToCameraTransform(frc::Transform3d robotToCamera)
Useful for pan and tilt mechanisms, or cameras on turrets.
Definition PhotonPoseEstimator.h:163
void SetMultiTagFallbackStrategy(PoseStrategy strategy)
Set the Position Estimation Strategy used in multi-tag mode when only one tag can be seen.
std::optional< EstimatedRobotPose > Update(const PhotonPipelineResult &result, std::optional< PhotonCamera::CameraMatrix > cameraMatrixData=std::nullopt, std::optional< PhotonCamera::DistortionMatrix > coeffsData=std::nullopt)
Update the pose estimator.
frc::Pose3d GetReferencePose() const
Return the reference position that is being used by the estimator.
Definition PhotonPoseEstimator.h:134
void SetLastPose(frc::Pose3d lastPose)
Update the stored last pose.
Definition PhotonPoseEstimator.h:173
void SetPoseStrategy(PoseStrategy strat)
Set the Position Estimation Strategy used by the Position Estimator.
Definition PhotonPoseEstimator.h:114
Definition VisionEstimation.h:32
PoseStrategy
Definition PhotonPoseEstimator.h:42
@ LOWEST_AMBIGUITY
Definition PhotonPoseEstimator.h:43
@ AVERAGE_BEST_TARGETS
Definition PhotonPoseEstimator.h:47
@ MULTI_TAG_PNP_ON_RIO
Definition PhotonPoseEstimator.h:49
@ CLOSEST_TO_CAMERA_HEIGHT
Definition PhotonPoseEstimator.h:44
@ CLOSEST_TO_LAST_POSE
Definition PhotonPoseEstimator.h:46
@ MULTI_TAG_PNP_ON_COPROCESSOR
Definition PhotonPoseEstimator.h:48
@ CLOSEST_TO_REFERENCE_POSE
Definition PhotonPoseEstimator.h:45
Definition PhotonPoseEstimator.h:52
EstimatedRobotPose(frc::Pose3d pose_, units::second_t time_, std::span< const PhotonTrackedTarget > targets, PoseStrategy strategy_)
Definition PhotonPoseEstimator.h:65
wpi::SmallVector< PhotonTrackedTarget, 10 > targetsUsed
A list of the targets used to compute this pose.
Definition PhotonPoseEstimator.h:60
frc::Pose3d estimatedPose
The estimated pose.
Definition PhotonPoseEstimator.h:54
PoseStrategy strategy
The strategy actually used to produce this pose.
Definition PhotonPoseEstimator.h:63
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:57