Package org.photonvision.targeting
Class PhotonTrackedTarget
java.lang.Object
org.photonvision.targeting.PhotonTrackedTarget
- All Implemented Interfaces:
ProtobufSerializable
,WPISerializable
,PhotonStructSerializable<PhotonTrackedTarget>
public class PhotonTrackedTarget
extends Object
implements ProtobufSerializable, PhotonStructSerializable<PhotonTrackedTarget>
-
Field Summary
FieldsModifier and TypeFieldDescriptiondouble
int
float
int
static final PhotonTrackedTargetSerde
double
double
static final PhotonTrackedTargetProto
double
double
-
Constructor Summary
ConstructorsConstructorDescriptionPhotonTrackedTarget
(double yaw, double pitch, double area, double skew, int fiducialId, int classId, float objDetectConf, Transform3d pose, Transform3d altPose, double ambiguity, List<TargetCorner> minAreaRectCorners, List<TargetCorner> detectedCorners) Construct a tracked target, given exactly 4 corners -
Method Summary
Modifier and TypeMethodDescriptionboolean
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 errordouble
getArea()
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 errorReturn a list of the n corners in image space (origin top left, x right, y down), in no particular order, detected for this target.int
Get the object detection class ID number, or -1 if not set.float
Get the object detection confidence, or -1 if not set.int
Get the fiducial ID, or -1 if not set.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 targetdouble
getPitch()
double
Get the ratio of best:alternate pose reprojection errors, called ambiguity.getSerde()
double
getSkew()
double
getYaw()
int
hashCode()
toString()
-
Field Details
-
yaw
-
pitch
-
area
-
skew
-
fiducialId
-
objDetectId
-
objDetectConf
-
bestCameraToTarget
-
altCameraToTarget
-
poseAmbiguity
-
minAreaRectCorners
-
detectedCorners
-
proto
-
photonStruct
-
-
Constructor Details
-
PhotonTrackedTarget
public PhotonTrackedTarget(double yaw, double pitch, double area, double skew, int fiducialId, int classId, float objDetectConf, Transform3d pose, Transform3d altPose, double ambiguity, List<TargetCorner> minAreaRectCorners, List<TargetCorner> detectedCorners) Construct a tracked target, given exactly 4 corners -
PhotonTrackedTarget
public PhotonTrackedTarget()
-
-
Method Details
-
getYaw
-
getPitch
-
getArea
-
getSkew
-
getFiducialId
Get the fiducial ID, or -1 if not set. -
getDetectedObjectClassID
Get the object detection class ID number, or -1 if not set. -
getDetectedObjectConfidence
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. -
getPoseAmbiguity
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. -
getMinAreaRectCorners
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 -
getDetectedCorners
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
-
getBestCameraToTarget
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 -
getAlternateCameraToTarget
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 -
hashCode
-
equals
-
toString
-
getSerde
- Specified by:
getSerde
in interfacePhotonStructSerializable<PhotonTrackedTarget>
-