PhotonVision C++ dev-v2025.0.0-beta-8-2-gbd1c5c03
Loading...
Searching...
No Matches
PhotonTrackedTarget.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 <cstddef>
21#include <string>
22#include <utility>
23#include <vector>
24
25#include <frc/geometry/Transform3d.h>
26#include <wpi/SmallVector.h>
27
29
30namespace photon {
31/**
32 * Represents a tracked target within a pipeline.
33 */
36
37 public:
39
40 explicit PhotonTrackedTarget(Base&& data) : Base(data) {}
41
42 template <typename... Args>
43 explicit PhotonTrackedTarget(Args&&... args)
44 : Base{std::forward<Args>(args)...} {}
45
46 /**
47 * Returns the target yaw (positive-left).
48 * @return The target yaw.
49 */
50 double GetYaw() const { return yaw; }
51
52 /**
53 * Returns the target pitch (positive-up)
54 * @return The target pitch.
55 */
56 double GetPitch() const { return pitch; }
57
58 /**
59 * Returns the target area (0-100).
60 * @return The target area.
61 */
62 double GetArea() const { return area; }
63
64 /**
65 * Returns the target skew (counter-clockwise positive).
66 * @return The target skew.
67 */
68 double GetSkew() const { return skew; }
69
70 /**
71 * Get the Fiducial ID of the target currently being tracked,
72 * or -1 if not set.
73 */
74 int GetFiducialId() const { return fiducialId; }
75
76 /**
77 * Get the Fiducial ID of the target currently being tracked,
78 * or -1 if not set.
79 */
80 int GetDetectedObjectClassID() const { return objDetectId; }
81
82 /**
83 * Get the object detection confidence, or -1 if not set. This will be between
84 * 0 and 1, with 1 indicating most confidence, and 0 least.
85 */
87
88 /**
89 * Return a list of the 4 corners in image space (origin top left, x right, y
90 * down), in no particular order, of the minimum area bounding rectangle of
91 * this target
92 */
93 const std::vector<photon::TargetCorner>& GetMinAreaRectCorners() const {
94 return minAreaRectCorners;
95 }
96
97 /**
98 * Return a list of the n corners in image space (origin top left, x right, y
99 * down), in no particular order, detected for this target.
100 * For fiducials, the order is known and is always counter-clock wise around
101 * the tag, like so
102 *
103 * -> +X 3 ----- 2
104 * | | |
105 * V + Y | |
106 * 0 ----- 1
107 */
108 const std::vector<photon::TargetCorner>& GetDetectedCorners() const {
109 return detectedCorners;
110 }
111
112 /**
113 * Get the ratio of best:alternate pose reprojection errors, called ambiguity.
114 * This is between 0 and 1 (0 being no ambiguity, and 1 meaning both have the
115 * same reprojection error). Numbers above 0.2 are likely to be ambiguous. -1
116 * if invalid.
117 */
118 double GetPoseAmbiguity() const { return poseAmbiguity; }
119
120 /**
121 * Get the transform that maps camera space (X = forward, Y = left, Z = up) to
122 * object/fiducial tag space (X forward, Y left, Z up) with the lowest
123 * reprojection error. The ratio between this and the alternate target's
124 * reprojection error is the ambiguity, which is between 0 and 1.
125 * @return The pose of the target relative to the robot.
126 */
127 frc::Transform3d GetBestCameraToTarget() const { return bestCameraToTarget; }
128
129 /**
130 * Get the transform that maps camera space (X = forward, Y = left, Z = up) to
131 * object/fiducial tag space (X forward, Y left, Z up) with the highest
132 * reprojection error
133 */
134 frc::Transform3d GetAlternateCameraToTarget() const {
135 return altCameraToTarget;
136 }
137
138 friend bool operator==(PhotonTrackedTarget const&,
139 PhotonTrackedTarget const&) = default;
140};
141} // namespace photon
142
Represents a tracked target within a pipeline.
Definition PhotonTrackedTarget.h:34
int GetFiducialId() const
Get the Fiducial ID of the target currently being tracked, or -1 if not set.
Definition PhotonTrackedTarget.h:74
const std::vector< photon::TargetCorner > & GetMinAreaRectCorners() const
Return a list of the 4 corners in image space (origin top left, x right, y down), in no particular or...
Definition PhotonTrackedTarget.h:93
frc::Transform3d GetBestCameraToTarget() const
Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag space...
Definition PhotonTrackedTarget.h:127
PhotonTrackedTarget(Args &&... args)
Definition PhotonTrackedTarget.h:43
PhotonTrackedTarget(Base &&data)
Definition PhotonTrackedTarget.h:40
frc::Transform3d GetAlternateCameraToTarget() const
Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag space...
Definition PhotonTrackedTarget.h:134
double GetArea() const
Returns the target area (0-100).
Definition PhotonTrackedTarget.h:62
double GetSkew() const
Returns the target skew (counter-clockwise positive).
Definition PhotonTrackedTarget.h:68
double GetPoseAmbiguity() const
Get the ratio of best:alternate pose reprojection errors, called ambiguity.
Definition PhotonTrackedTarget.h:118
float GetDetectedObjectConfidence() const
Get the object detection confidence, or -1 if not set.
Definition PhotonTrackedTarget.h:86
const std::vector< photon::TargetCorner > & GetDetectedCorners() const
Return a list of the n corners in image space (origin top left, x right, y down), in no particular or...
Definition PhotonTrackedTarget.h:108
double GetPitch() const
Returns the target pitch (positive-up)
Definition PhotonTrackedTarget.h:56
friend bool operator==(PhotonTrackedTarget const &, PhotonTrackedTarget const &)=default
int GetDetectedObjectClassID() const
Get the Fiducial ID of the target currently being tracked, or -1 if not set.
Definition PhotonTrackedTarget.h:80
double GetYaw() const
Returns the target yaw (positive-left).
Definition PhotonTrackedTarget.h:50
Definition VisionEstimation.h:32
Definition PhotonTrackedTargetStruct.h:31
int32_t objDetectId
Definition PhotonTrackedTargetStruct.h:37
std::vector< photon::TargetCorner > minAreaRectCorners
Definition PhotonTrackedTargetStruct.h:42
double poseAmbiguity
Definition PhotonTrackedTargetStruct.h:41
std::vector< photon::TargetCorner > detectedCorners
Definition PhotonTrackedTargetStruct.h:43
double pitch
Definition PhotonTrackedTargetStruct.h:33
int32_t fiducialId
Definition PhotonTrackedTargetStruct.h:36
double yaw
Definition PhotonTrackedTargetStruct.h:32
frc::Transform3d bestCameraToTarget
Definition PhotonTrackedTargetStruct.h:39
frc::Transform3d altCameraToTarget
Definition PhotonTrackedTargetStruct.h:40
double area
Definition PhotonTrackedTargetStruct.h:34
float objDetectConf
Definition PhotonTrackedTargetStruct.h:38
double skew
Definition PhotonTrackedTargetStruct.h:35