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>
70 std::span<const PhotonTrackedTarget> targets,
74 targetsUsed(targets.data(), targets.data() + targets.size()),
95 frc::Transform3d robotToCamera);
109 "Use individual estimation methods with the 2 argument constructor "
113 frc::Transform3d robotToCamera);
128 [[deprecated(
"Use individual estimation methods instead.")]]
139 [[deprecated(
"Use individual estimation methods instead.")]]
141 if (strategy != strat) {
142 InvalidatePoseCache();
154 [[deprecated(
"Use individual estimation methods instead.")]]
163 [[deprecated(
"Use individual estimation methods instead.")]]
165 return referencePose;
175 [[deprecated(
"Use individual estimation methods instead.")]]
177 if (this->referencePose != referencePose) {
178 InvalidatePoseCache();
180 this->referencePose = referencePose;
188 return m_robotToCamera;
198 m_robotToCamera = robotToCamera;
208 [[deprecated(
"Use individual estimation methods instead.")]]
210 this->lastPose = lastPose;
222 frc::Rotation2d heading) {
223 this->headingBuffer.AddSample(timestamp, heading);
235 frc::Rotation3d heading) {
249 frc::Rotation2d heading) {
250 headingBuffer.Clear();
264 frc::Rotation3d heading) {
281 [[deprecated(
"Use individual estimation methods instead.")]]
282 std::optional<EstimatedRobotPose>
Update(
284 std::optional<photon::PhotonCamera::CameraMatrix> cameraMatrixData =
286 std::optional<photon::PhotonCamera::DistortionMatrix> coeffsData =
288 std::optional<ConstrainedSolvepnpParams> constrainedPnpParams =
414 bool headingFree,
double headingScaleFactor);
417 frc::AprilTagFieldLayout aprilTags;
421 frc::Transform3d m_robotToCamera;
423 frc::Pose3d lastPose;
424 frc::Pose3d referencePose;
426 units::second_t poseCacheTimestamp;
428 frc::TimeInterpolatableBuffer<frc::Rotation2d> headingBuffer;
430 inline static int InstanceCount = 1;
432 inline void InvalidatePoseCache() { poseCacheTimestamp = -1_s; }
446 return Update(result, std::nullopt, std::nullopt, std::nullopt, strategy);
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,
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