29#include <frc/apriltag/AprilTagFieldLayout.h>
30#include <frc/geometry/Pose3d.h>
31#include <frc/geometry/Transform3d.h>
32#include <opencv2/core/mat.hpp>
66 std::span<const PhotonTrackedTarget> targets,
70 targetsUsed(targets.data(), targets.data() + targets.size()),
93 frc::Transform3d robotToCamera);
115 if (strategy != strat) {
116 InvalidatePoseCache();
143 if (this->referencePose != referencePose) {
144 InvalidatePoseCache();
146 this->referencePose = referencePose;
154 return m_robotToCamera;
164 m_robotToCamera = robotToCamera;
173 inline void SetLastPose(frc::Pose3d lastPose) { this->lastPose = lastPose; }
186 std::optional<EstimatedRobotPose>
Update(
188 std::optional<PhotonCamera::CameraMatrix> cameraMatrixData = std::nullopt,
189 std::optional<PhotonCamera::DistortionMatrix> coeffsData = std::nullopt);
192 frc::AprilTagFieldLayout aprilTags;
196 frc::Transform3d m_robotToCamera;
198 frc::Pose3d lastPose;
199 frc::Pose3d referencePose;
201 units::second_t poseCacheTimestamp;
203 inline static int InstanceCount = 0;
205 inline void InvalidatePoseCache() { poseCacheTimestamp = -1_s; }
207 std::optional<EstimatedRobotPose>
Update(
209 std::optional<PhotonCamera::CameraMatrix> cameraMatrixData,
210 std::optional<PhotonCamera::DistortionMatrix> coeffsData,
220 std::optional<EstimatedRobotPose> LowestAmbiguityStrategy(
231 std::optional<EstimatedRobotPose> ClosestToCameraHeightStrategy(
243 std::optional<EstimatedRobotPose> ClosestToReferencePoseStrategy(
251 std::optional<EstimatedRobotPose> MultiTagOnCoprocStrategy(
261 std::optional<EstimatedRobotPose> MultiTagOnRioStrategy(
263 std::optional<PhotonCamera::CameraMatrix> camMat,
264 std::optional<PhotonCamera::DistortionMatrix> distCoeffs);
272 std::optional<EstimatedRobotPose> AverageBestTargetsStrategy(
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