PhotonVision C++ v2026.0.0-alpha-2
Loading...
Searching...
No Matches
VisionEstimation.h
Go to the documentation of this file.
1/*
2 * Copyright (C) Photon Vision.
3 *
4 * This program is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
8 *
9 * This program is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
13 *
14 * You should have received a copy of the GNU General Public License
15 * along with this program. If not, see <https://www.gnu.org/licenses/>.
16 */
17
18#pragma once
19
20#include <vector>
21
22#include <Eigen/Core>
23#include <frc/apriltag/AprilTag.h>
24#include <frc/apriltag/AprilTagFieldLayout.h>
25
26#include "TargetModel.h"
29
30namespace photon {
31namespace VisionEstimation {
32
33std::vector<frc::AprilTag> GetVisibleLayoutTags(
34 const std::vector<PhotonTrackedTarget>& visTags,
35 const frc::AprilTagFieldLayout& layout);
36
37std::optional<photon::PnpResult> EstimateCamPosePNP(
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);
42
43std::optional<photon::PnpResult> EstimateRobotPoseConstrainedSolvePNP(
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,
48 const frc::AprilTagFieldLayout& layout, const photon::TargetModel& tagModel,
49 bool headingFree, frc::Rotation2d gyroTheta, double gyroErrorScaleFac);
50
51} // namespace VisionEstimation
52} // namespace photon
Definition TargetModel.h:28
std::vector< frc::AprilTag > GetVisibleLayoutTags(const std::vector< PhotonTrackedTarget > &visTags, const frc::AprilTagFieldLayout &layout)
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)
Definition VisionEstimation.h:30