31namespace VisionEstimation {
34 const std::vector<PhotonTrackedTarget>& visTags,
35 const frc::AprilTagFieldLayout& layout);
38 const Eigen::Matrix<double, 3, 3>& cameraMatrix,
39 const Eigen::Matrix<double, 8, 1>& distCoeffs,
40 const std::vector<PhotonTrackedTarget>& visTags,
41 const frc::AprilTagFieldLayout& layout,
const TargetModel& tagModel);
44 const Eigen::Matrix<double, 3, 3>& cameraMatrix,
45 const Eigen::Matrix<double, 8, 1>& distCoeffs,
46 const std::vector<photon::PhotonTrackedTarget>& visTags,
47 const frc::Transform3d& robot2Camera,
const frc::Pose3d& robotPoseSeed,
49 bool headingFree, frc::Rotation2d gyroTheta,
double gyroErrorScaleFac);
std::optional< photon::PnpResult > EstimateRobotPoseConstrainedSolvePNP(const Eigen::Matrix< double, 3, 3 > &cameraMatrix, const Eigen::Matrix< double, 8, 1 > &distCoeffs, const std::vector< photon::PhotonTrackedTarget > &visTags, const frc::Transform3d &robot2Camera, const frc::Pose3d &robotPoseSeed, const frc::AprilTagFieldLayout &layout, const photon::TargetModel &tagModel, bool headingFree, frc::Rotation2d gyroTheta, double gyroErrorScaleFac)
std::optional< photon::PnpResult > EstimateCamPosePNP(const Eigen::Matrix< double, 3, 3 > &cameraMatrix, const Eigen::Matrix< double, 8, 1 > &distCoeffs, const std::vector< PhotonTrackedTarget > &visTags, const frc::AprilTagFieldLayout &layout, const TargetModel &tagModel)