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>
75 std::span<const PhotonTrackedTarget> targets,
79 targetsUsed(targets.data(), targets.data() + targets.size()),
102 frc::Transform3d robotToCamera);
124 if (strategy != strat) {
125 InvalidatePoseCache();
152 if (this->referencePose != referencePose) {
153 InvalidatePoseCache();
155 this->referencePose = referencePose;
163 return m_robotToCamera;
173 m_robotToCamera = robotToCamera;
182 inline void SetLastPose(frc::Pose3d lastPose) { this->lastPose = lastPose; }
193 frc::Rotation2d heading) {
194 this->headingBuffer.AddSample(timestamp, heading);
206 frc::Rotation3d heading) {
220 frc::Rotation2d heading) {
221 headingBuffer.Clear();
235 frc::Rotation3d heading) {
251 std::optional<EstimatedRobotPose>
Update(
253 std::optional<photon::PhotonCamera::CameraMatrix> cameraMatrixData =
255 std::optional<photon::PhotonCamera::DistortionMatrix> coeffsData =
257 std::optional<ConstrainedSolvepnpParams> constrainedPnpParams =
261 frc::AprilTagFieldLayout aprilTags;
265 frc::Transform3d m_robotToCamera;
267 frc::Pose3d lastPose;
268 frc::Pose3d referencePose;
270 units::second_t poseCacheTimestamp;
272 frc::TimeInterpolatableBuffer<frc::Rotation2d> headingBuffer;
274 inline static int InstanceCount = 1;
276 inline void InvalidatePoseCache() { poseCacheTimestamp = -1_s; }
290 return Update(result, std::nullopt, std::nullopt, std::nullopt, strategy);
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,
307 std::optional<EstimatedRobotPose> LowestAmbiguityStrategy(
308 PhotonPipelineResult result);
318 std::optional<EstimatedRobotPose> ClosestToCameraHeightStrategy(
319 PhotonPipelineResult result);
330 std::optional<EstimatedRobotPose> ClosestToReferencePoseStrategy(
331 PhotonPipelineResult result);
338 std::optional<EstimatedRobotPose> MultiTagOnCoprocStrategy(
339 PhotonPipelineResult result);
348 std::optional<EstimatedRobotPose> MultiTagOnRioStrategy(
349 PhotonPipelineResult result,
350 std::optional<PhotonCamera::CameraMatrix> camMat,
351 std::optional<PhotonCamera::DistortionMatrix> distCoeffs);
360 std::optional<EstimatedRobotPose> PnpDistanceTrigSolveStrategy(
361 PhotonPipelineResult result);
369 std::optional<EstimatedRobotPose> AverageBestTargetsStrategy(
370 PhotonPipelineResult result);
372 std::optional<EstimatedRobotPose> ConstrainedPnpStrategy(
374 std::optional<photon::PhotonCamera::CameraMatrix> camMat,
375 std::optional<photon::PhotonCamera::DistortionMatrix> distCoeffs,
376 std::optional<ConstrainedSolvepnpParams> constrainedPnpParams);
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