Package org.photonvision.targeting
Class PhotonTrackedTarget
java.lang.Object
org.photonvision.targeting.PhotonTrackedTarget
- All Implemented Interfaces:
edu.wpi.first.util.protobuf.ProtobufSerializable
,edu.wpi.first.util.WPISerializable
public class PhotonTrackedTarget
extends Object
implements edu.wpi.first.util.protobuf.ProtobufSerializable
-
Nested Class Summary
Nested Classes -
Field Summary
FieldsModifier and TypeFieldDescriptionstatic final PhotonTrackedTargetProto
static final PhotonTrackedTarget.APacketSerde
-
Constructor Summary
ConstructorsConstructorDescriptionPhotonTrackedTarget
(double yaw, double pitch, double area, double skew, int fiducialId, int classId, float objDetectConf, edu.wpi.first.math.geometry.Transform3d pose, edu.wpi.first.math.geometry.Transform3d altPose, double ambiguity, List<TargetCorner> minAreaRectCorners, List<TargetCorner> detectedCorners) Construct a tracked target, given exactly 4 corners -
Method Summary
Modifier and TypeMethodDescriptionboolean
edu.wpi.first.math.geometry.Transform3d
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()
edu.wpi.first.math.geometry.Transform3d
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.double
getSkew()
double
getYaw()
int
hashCode()
toString()
-
Field Details
-
serde
-
proto
-
-
Constructor Details
-
PhotonTrackedTarget
public PhotonTrackedTarget(double yaw, double pitch, double area, double skew, int fiducialId, int classId, float objDetectConf, edu.wpi.first.math.geometry.Transform3d pose, edu.wpi.first.math.geometry.Transform3d altPose, double ambiguity, List<TargetCorner> minAreaRectCorners, List<TargetCorner> detectedCorners) Construct a tracked target, given exactly 4 corners
-
-
Method Details
-
getYaw
public double getYaw() -
getPitch
public double getPitch() -
getArea
public double getArea() -
getSkew
public double getSkew() -
getFiducialId
public int getFiducialId()Get the fiducial ID, or -1 if not set. -
getDetectedObjectClassID
public int getDetectedObjectClassID()Get the object detection class ID number, or -1 if not set. -
getDetectedObjectConfidence
public float 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
public double getPoseAmbiguity()Get the ratio of best:alternate pose reprojection errors, called ambiguity. This is betweeen 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
public edu.wpi.first.math.geometry.Transform3d 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
public edu.wpi.first.math.geometry.Transform3d 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
public int hashCode() -
equals
-
toString
-