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
  • Field Details

  • 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

      public List<TargetCorner> 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

      public List<TargetCorner> 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()
      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