Class PhotonTrackedTarget

java.lang.Object
org.photonvision.targeting.PhotonTrackedTarget
All Implemented Interfaces:
PhotonStructSerializable<PhotonTrackedTarget>, org.wpilib.util.protobuf.ProtobufSerializable, org.wpilib.util.WPISerializable

public class PhotonTrackedTarget extends Object implements org.wpilib.util.protobuf.ProtobufSerializable, PhotonStructSerializable<PhotonTrackedTarget>
Information about a detected target.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    org.wpilib.math.geometry.Transform3d
    The transform with the highest reprojection error
    double
    The area (how much of the camera feed the bounding box takes up) as a percentage (0-100).
    org.wpilib.math.geometry.Transform3d
    The transform with the lowest reprojection error
    Corners from the corner detection method used
    int
    The fiducial ID, or -1 if it doesn't exist for this target.
    Corners from the min-area rectangle bounding the target
    float
    The object detection confidence, or -1 if it doesn't exist for this target.
    int
    The object detection class ID, or -1 if it doesn't exist for this target.
    PhotonTrackedTarget PhotonStruct for serialization.
    double
    The pitch of the target in degrees, with up being the positive direction.
    double
    The ratio (best:alt) of reprojection errors
    PhotonTrackedTarget protobuf for serialization.
    double
    The skew of the target in degrees, with counterclockwise being the positive direction.
    double
    The yaw of the target in degrees, with left being the positive direction.
  • Constructor Summary

    Constructors
    Constructor
    Description
    Used for serialization.
    PhotonTrackedTarget(double yaw, double pitch, double area, double skew, int fiducialId, int classId, float objDetectConf, org.wpilib.math.geometry.Transform3d pose, org.wpilib.math.geometry.Transform3d altPose, double ambiguity, List<TargetCorner> minAreaRectCorners, List<TargetCorner> detectedCorners)
    Construct a tracked target, given exactly 4 corners
  • Method Summary

    Modifier and Type
    Method
    Description
    boolean
     
    org.wpilib.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 error
    double
    The area (how much of the camera feed the bounding box takes up) as a percentage (0-100).
    org.wpilib.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 error
    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.
    int
    Get the object detection class ID number, or -1 if it doesn't exist for this target.
    float
    Get the object detection confidence, or -1 if it doesn't exist for this target.
    int
    Get 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 target
    double
     
    double
    Get the ratio of best:alternate pose reprojection errors, called ambiguity.
    Returns the PhotonStruct serializer for this type.
    double
     
    double
     
    int
     
     

    Methods inherited from class Object

    clone, finalize, getClass, notify, notifyAll, wait, wait, wait
  • Field Details

    • yaw

      public double yaw
      The yaw of the target in degrees, with left being the positive direction.
    • pitch

      public double pitch
      The pitch of the target in degrees, with up being the positive direction.
    • area

      public double area
      The area (how much of the camera feed the bounding box takes up) as a percentage (0-100).
    • skew

      public double skew
      The skew of the target in degrees, with counterclockwise being the positive direction.
    • fiducialId

      public int fiducialId
      The fiducial ID, or -1 if it doesn't exist for this target.
    • objDetectId

      public int objDetectId
      The object detection class ID, or -1 if it doesn't exist for this target.
    • objDetectConf

      public float objDetectConf
      The object detection confidence, or -1 if it doesn't exist for this target.
    • bestCameraToTarget

      public org.wpilib.math.geometry.Transform3d bestCameraToTarget
      The transform with the lowest reprojection error
    • altCameraToTarget

      public org.wpilib.math.geometry.Transform3d altCameraToTarget
      The transform with the highest reprojection error
    • poseAmbiguity

      public double 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

      public static final PhotonTrackedTargetProto 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, org.wpilib.math.geometry.Transform3d pose, org.wpilib.math.geometry.Transform3d altPose, double ambiguity, List<TargetCorner> minAreaRectCorners, List<TargetCorner> detectedCorners)
      Construct a tracked target, given exactly 4 corners
      Parameters:
      yaw - The yaw of the target
      pitch - The pitch of the target
      area - The area of the target as a percentage of the camera image
      skew - The skew of the target
      fiducialId - The fiduical tag ID
      classId - The object detection class ID
      objDetectConf - The object detection confidence
      pose - The best camera to target transform
      altPose - The alternate camera to target transform
      ambiguity - The ambiguity (best:alternate ratio of reprojection errors) of the target
      minAreaRectCorners - The corners of minimum area bounding box of the target
      detectedCorners - The detected corners of the target
    • PhotonTrackedTarget

      Used for serialization.
  • Method Details

    • getYaw

      public double getYaw()
    • getPitch

      public double getPitch()
    • getArea

      public double 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

      public double getSkew()
    • getFiducialId

      public int 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

      public double 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

      public org.wpilib.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
      Returns:
      The transform with the lowest reprojection error (the best)
    • getAlternateCameraToTarget

      public org.wpilib.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
      Returns:
      The transform with the highest reprojection error (the alternate)
    • hashCode

      public int hashCode()
      Overrides:
      hashCode in class Object
    • equals

      public boolean equals(Object obj)
      Overrides:
      equals in class Object
    • toString

      public String toString()
      Overrides:
      toString in class Object
    • getSerde

      Description copied from interface: PhotonStructSerializable
      Returns the PhotonStruct serializer for this type.
      Specified by:
      getSerde in interface PhotonStructSerializable<PhotonTrackedTarget>
      Returns:
      The PhotonStruct serializer