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>
Information about a detected target.
-
Field Summary
FieldsModifier and TypeFieldDescriptionThe transform with the highest reprojection errordoubleThe area (how much of the camera feed the bounding box takes up) as a percentage (0-100).The transform with the lowest reprojection errorCorners from the corner detection method usedintThe fiducial ID, or -1 if it doesn't exist for this target.Corners from the min-area rectangle bounding the targetfloatThe object detection confidence, or -1 if it doesn't exist for this target.intThe object detection class ID, or -1 if it doesn't exist for this target.static final PhotonTrackedTargetSerdePhotonTrackedTarget PhotonStruct for serialization.doubleThe pitch of the target in degrees, with up being the positive direction.doubleThe ratio (best:alt) of reprojection errorsstatic final PhotonTrackedTargetProtoPhotonTrackedTarget protobuf for serialization.doubleThe skew of the target in degrees, with counterclockwise being the positive direction.doubleThe yaw of the target in degrees, with left being the positive direction. -
Constructor Summary
ConstructorsConstructorDescriptionUsed for serialization.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 -
Method Summary
Modifier and TypeMethodDescriptionbooleanGet 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 errordoublegetArea()The area (how much of the camera feed the bounding box takes up) as a percentage (0-100).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.intGet the object detection class ID number, or -1 if it doesn't exist for this target.floatGet the object detection confidence, or -1 if it doesn't exist for this target.intGet the fiducial ID, or -1 if it doesn't exist for this target.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 targetdoublegetPitch()doubleGet the ratio of best:alternate pose reprojection errors, called ambiguity.getSerde()Returns the PhotonStruct serializer for this type.doublegetSkew()doublegetYaw()inthashCode()toString()
-
Field Details
-
yaw
The yaw of the target in degrees, with left being the positive direction. -
pitch
The pitch of the target in degrees, with up being the positive direction. -
area
The area (how much of the camera feed the bounding box takes up) as a percentage (0-100). -
skew
The skew of the target in degrees, with counterclockwise being the positive direction. -
fiducialId
The fiducial ID, or -1 if it doesn't exist for this target. -
objDetectId
The object detection class ID, or -1 if it doesn't exist for this target. -
objDetectConf
The object detection confidence, or -1 if it doesn't exist for this target. -
bestCameraToTarget
The transform with the lowest reprojection error -
altCameraToTarget
The transform with the highest reprojection error -
poseAmbiguity
The ratio (best:alt) of reprojection errors -
minAreaRectCorners
Corners from the min-area rectangle bounding the target -
detectedCorners
Corners from the corner detection method used -
proto
PhotonTrackedTarget protobuf for serialization. -
photonStruct
PhotonTrackedTarget PhotonStruct for serialization.
-
-
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- Parameters:
yaw- The yaw of the targetpitch- The pitch of the targetarea- The area of the target as a percentage of the camera imageskew- The skew of the targetfiducialId- The fiduical tag IDclassId- The object detection class IDobjDetectConf- The object detection confidencepose- The best camera to target transformaltPose- The alternate camera to target transformambiguity- The ambiguity (best:alternate ratio of reprojection errors) of the targetminAreaRectCorners- The corners of minimum area bounding box of the targetdetectedCorners- The detected corners of the target
-
PhotonTrackedTarget
public PhotonTrackedTarget()Used for serialization.
-
-
Method Details
-
getYaw
-
getPitch
-
getArea
The area (how much of the camera feed the bounding box takes up) as a percentage (0-100).- Returns:
- The area as a percentage
-
getSkew
-
getFiducialId
Get the fiducial ID, or -1 if it doesn't exist for this target.- Returns:
- The fiducial ID
-
getDetectedObjectClassID
Get the object detection class ID number, or -1 if it doesn't exist for this target.- Returns:
- The object detection class ID
-
getDetectedObjectConfidence
Get the object detection confidence, or -1 if it doesn't exist for this target. This will be between 0 and 1, with 1 indicating most confidence, and 0 least.- Returns:
- The object detection confidence
-
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.- Returns:
- The pose ambiguity
-
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- Returns:
- The list of corners
-
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
- Returns:
- The list of detected corners for this target
-
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- Returns:
- The transform with the lowest reprojection error (the best)
-
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- Returns:
- The transform with the highest reprojection error (the alternate)
-
hashCode
-
equals
-
toString
-
getSerde
Description copied from interface:PhotonStructSerializableReturns the PhotonStruct serializer for this type.- Specified by:
getSerdein interfacePhotonStructSerializable<PhotonTrackedTarget>- Returns:
- The PhotonStruct serializer
-