PhotonVision C++ dev-v2025.0.0-beta-8-2-gbd1c5c03
Loading...
Searching...
No Matches
photon::PhotonTrackedTarget Class Reference

Represents a tracked target within a pipeline. More...

#include <photon/targeting/PhotonTrackedTarget.h>

Inheritance diagram for photon::PhotonTrackedTarget:
photon::PhotonTrackedTarget_PhotonStruct

Public Member Functions

 PhotonTrackedTarget ()=default
 
 PhotonTrackedTarget (Base &&data)
 
template<typename... Args>
 PhotonTrackedTarget (Args &&... args)
 
double GetYaw () const
 Returns the target yaw (positive-left).
 
double GetPitch () const
 Returns the target pitch (positive-up)
 
double GetArea () const
 Returns the target area (0-100).
 
double GetSkew () const
 Returns the target skew (counter-clockwise positive).
 
int GetFiducialId () const
 Get the Fiducial ID of the target currently being tracked, or -1 if not set.
 
int GetDetectedObjectClassID () const
 Get the Fiducial ID of the target currently being tracked, or -1 if not set.
 
float GetDetectedObjectConfidence () const
 Get the object detection confidence, or -1 if not set.
 
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 order, of the minimum area bounding rectangle of this target.
 
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 order, detected for this target.
 
double GetPoseAmbiguity () const
 Get the ratio of best:alternate pose reprojection errors, called ambiguity.
 
frc::Transform3d GetBestCameraToTarget () const
 Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag space (X forward, Y left, Z up) with the lowest reprojection error.
 
frc::Transform3d GetAlternateCameraToTarget () const
 Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag space (X forward, Y left, Z up) with the highest reprojection error.
 

Friends

bool operator== (PhotonTrackedTarget const &, PhotonTrackedTarget const &)=default
 

Additional Inherited Members

- Public Attributes inherited from photon::PhotonTrackedTarget_PhotonStruct
double yaw
 
double pitch
 
double area
 
double skew
 
int32_t fiducialId
 
int32_t objDetectId
 
float objDetectConf
 
frc::Transform3d bestCameraToTarget
 
frc::Transform3d altCameraToTarget
 
double poseAmbiguity
 
std::vector< photon::TargetCornerminAreaRectCorners
 
std::vector< photon::TargetCornerdetectedCorners
 

Detailed Description

Represents a tracked target within a pipeline.

Constructor & Destructor Documentation

◆ PhotonTrackedTarget() [1/3]

photon::PhotonTrackedTarget::PhotonTrackedTarget ( )
default

◆ PhotonTrackedTarget() [2/3]

photon::PhotonTrackedTarget::PhotonTrackedTarget ( Base && data)
inlineexplicit

◆ PhotonTrackedTarget() [3/3]

template<typename... Args>
photon::PhotonTrackedTarget::PhotonTrackedTarget ( Args &&... args)
inlineexplicit

Member Function Documentation

◆ GetAlternateCameraToTarget()

frc::Transform3d photon::PhotonTrackedTarget::GetAlternateCameraToTarget ( ) const
inline

Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag space (X forward, Y left, Z up) with the highest reprojection error.

◆ GetArea()

double photon::PhotonTrackedTarget::GetArea ( ) const
inline

Returns the target area (0-100).

Returns
The target area.

◆ GetBestCameraToTarget()

frc::Transform3d photon::PhotonTrackedTarget::GetBestCameraToTarget ( ) const
inline

Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag space (X forward, Y left, Z up) with the lowest reprojection error.

The ratio between this and the alternate target's reprojection error is the ambiguity, which is between 0 and 1.

Returns
The pose of the target relative to the robot.

◆ GetDetectedCorners()

const std::vector< photon::TargetCorner > & photon::PhotonTrackedTarget::GetDetectedCorners ( ) const
inline

Return a list of the n corners in image space (origin top left, x right, y down), in no particular order, detected for this target.

For fiducials, the order is known and is always counter-clock wise around the tag, like so

-> +X 3 --— 2 | | | V + Y | | 0 --— 1

◆ GetDetectedObjectClassID()

int photon::PhotonTrackedTarget::GetDetectedObjectClassID ( ) const
inline

Get the Fiducial ID of the target currently being tracked, or -1 if not set.

◆ GetDetectedObjectConfidence()

float photon::PhotonTrackedTarget::GetDetectedObjectConfidence ( ) const
inline

Get the object detection confidence, or -1 if not set.

This will be between 0 and 1, with 1 indicating most confidence, and 0 least.

◆ GetFiducialId()

int photon::PhotonTrackedTarget::GetFiducialId ( ) const
inline

Get the Fiducial ID of the target currently being tracked, or -1 if not set.

◆ GetMinAreaRectCorners()

const std::vector< photon::TargetCorner > & photon::PhotonTrackedTarget::GetMinAreaRectCorners ( ) const
inline

Return a list of the 4 corners in image space (origin top left, x right, y down), in no particular order, of the minimum area bounding rectangle of this target.

◆ GetPitch()

double photon::PhotonTrackedTarget::GetPitch ( ) const
inline

Returns the target pitch (positive-up)

Returns
The target pitch.

◆ GetPoseAmbiguity()

double photon::PhotonTrackedTarget::GetPoseAmbiguity ( ) const
inline

Get the ratio of best:alternate pose reprojection errors, called ambiguity.

This is between 0 and 1 (0 being no ambiguity, and 1 meaning both have the same reprojection error). Numbers above 0.2 are likely to be ambiguous. -1 if invalid.

◆ GetSkew()

double photon::PhotonTrackedTarget::GetSkew ( ) const
inline

Returns the target skew (counter-clockwise positive).

Returns
The target skew.

◆ GetYaw()

double photon::PhotonTrackedTarget::GetYaw ( ) const
inline

Returns the target yaw (positive-left).

Returns
The target yaw.

Friends And Related Symbol Documentation

◆ operator==

bool operator== ( PhotonTrackedTarget const & ,
PhotonTrackedTarget const &  )
friend

The documentation for this class was generated from the following file: