PhotonVision C++ dev-v2025.0.0-beta-8-2-gbd1c5c03
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 <utility>
21#include <vector>
22
23#include <Eigen/Core>
24#include <frc/apriltag/AprilTag.h>
25#include <frc/apriltag/AprilTagFieldLayout.h>
26
27#include "OpenCVHelp.h"
28#include "TargetModel.h"
31
32namespace photon {
33namespace VisionEstimation {
34
35[[maybe_unused]] static std::vector<frc::AprilTag> GetVisibleLayoutTags(
36 const std::vector<PhotonTrackedTarget>& visTags,
37 const frc::AprilTagFieldLayout& layout) {
38 std::vector<frc::AprilTag> retVal{};
39 for (const auto& tag : visTags) {
40 int id = tag.GetFiducialId();
41 auto maybePose = layout.GetTagPose(id);
42 if (maybePose) {
43 retVal.emplace_back(frc::AprilTag{id, maybePose.value()});
44 }
45 }
46 return retVal;
47}
48
49#include <iostream>
50
51static std::optional<PnpResult> EstimateCamPosePNP(
52 const Eigen::Matrix<double, 3, 3>& cameraMatrix,
53 const Eigen::Matrix<double, 8, 1>& distCoeffs,
54 const std::vector<PhotonTrackedTarget>& visTags,
55 const frc::AprilTagFieldLayout& layout, const TargetModel& tagModel) {
56 if (visTags.size() == 0) {
57 return PnpResult();
58 }
59
60 std::vector<photon::TargetCorner> corners{};
61 std::vector<frc::AprilTag> knownTags{};
62
63 for (const auto& tgt : visTags) {
64 int id = tgt.GetFiducialId();
65 auto maybePose = layout.GetTagPose(id);
66 if (maybePose) {
67 knownTags.emplace_back(frc::AprilTag{id, maybePose.value()});
68 auto currentCorners = tgt.GetDetectedCorners();
69 corners.insert(corners.end(), currentCorners.begin(),
70 currentCorners.end());
71 }
72 }
73 if (knownTags.size() == 0 || corners.size() == 0 || corners.size() % 4 != 0) {
74 return PnpResult{};
75 }
76
77 std::vector<cv::Point2f> points = OpenCVHelp::CornersToPoints(corners);
78
79 if (knownTags.size() == 1) {
80 auto camToTag = OpenCVHelp::SolvePNP_Square(cameraMatrix, distCoeffs,
81 tagModel.GetVertices(), points);
82 if (!camToTag) {
83 return PnpResult{};
84 }
85 frc::Pose3d bestPose =
86 knownTags[0].pose.TransformBy(camToTag->best.Inverse());
87 frc::Pose3d altPose{};
88 if (camToTag->ambiguity != 0) {
89 altPose = knownTags[0].pose.TransformBy(camToTag->alt.Inverse());
90 }
91 frc::Pose3d o{};
92 PnpResult result{};
93 result.best = frc::Transform3d{o, bestPose};
94 result.alt = frc::Transform3d{o, altPose};
95 result.ambiguity = camToTag->ambiguity;
96 result.bestReprojErr = camToTag->bestReprojErr;
97 result.altReprojErr = camToTag->altReprojErr;
98 return result;
99 } else {
100 std::vector<frc::Translation3d> objectTrls{};
101 for (const auto& tag : knownTags) {
102 auto verts = tagModel.GetFieldVertices(tag.pose);
103 objectTrls.insert(objectTrls.end(), verts.begin(), verts.end());
104 }
105 auto ret = OpenCVHelp::SolvePNP_SQPNP(cameraMatrix, distCoeffs, objectTrls,
106 points);
107 if (ret) {
108 // Invert best/alt transforms
109 ret->best = ret->best.Inverse();
110 ret->alt = ret->alt.Inverse();
111 }
112
113 return ret;
114 }
115}
116
117} // namespace VisionEstimation
118} // namespace photon
Definition TargetModel.h:28
std::vector< frc::Translation3d > GetVertices() const
Definition TargetModel.h:103
std::vector< frc::Translation3d > GetFieldVertices(const frc::Pose3d &targetPose) const
Definition TargetModel.h:78
static std::optional< photon::PnpResult > SolvePNP_SQPNP(const Eigen::Matrix< double, 3, 3 > &cameraMatrix, const Eigen::Matrix< double, 8, 1 > &distCoeffs, std::vector< frc::Translation3d > modelTrls, std::vector< cv::Point2f > imagePoints)
Definition OpenCVHelp.h:275
static std::optional< photon::PnpResult > SolvePNP_Square(const Eigen::Matrix< double, 3, 3 > &cameraMatrix, const Eigen::Matrix< double, 8, 1 > &distCoeffs, std::vector< frc::Translation3d > modelTrls, std::vector< cv::Point2f > imagePoints)
Definition OpenCVHelp.h:208
static std::vector< cv::Point2f > CornersToPoints(const std::vector< std::pair< float, float > > &corners)
Definition OpenCVHelp.h:121
static std::optional< 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:51
static std::vector< frc::AprilTag > GetVisibleLayoutTags(const std::vector< PhotonTrackedTarget > &visTags, const frc::AprilTagFieldLayout &layout)
Definition VisionEstimation.h:35
Definition VisionEstimation.h:32
frc::Transform3d best
Definition PnpResultStruct.h:30
Definition PnpResult.h:29