Package frclib.vision

Class FrcPhotonVision.DetectedObject

java.lang.Object
frclib.vision.FrcPhotonVision.DetectedObject
All Implemented Interfaces:
TrcVisionTargetInfo.ObjectInfo
Enclosing class:
FrcPhotonVision

public class FrcPhotonVision.DetectedObject extends Object implements TrcVisionTargetInfo.ObjectInfo
This class encapsulates info of the detected object. It extends TrcOpenCvDetector.DetectedObject that requires it to provide a method to return the detected object rect and area.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    final double
     
    final org.opencv.core.Point[]
     
    final double
     
    final double
     
    final org.opencv.core.Rect
     
    final TrcPose2D
     
    final double
     
    final org.photonvision.targeting.PhotonTrackedTarget
     
    final TrcPose2D
     
    final double
     
  • Constructor Summary

    Constructors
    Constructor
    Description
    DetectedObject(double timestamp, org.photonvision.targeting.PhotonTrackedTarget target, edu.wpi.first.math.geometry.Transform3d robotToCamera, TrcPose2D robotPose)
    Constructor: Creates an instance of the object.
  • Method Summary

    Modifier and Type
    Method
    Description
    addTransformToTarget(org.photonvision.targeting.PhotonTrackedTarget target, edu.wpi.first.math.geometry.Transform3d robotToCam, edu.wpi.first.math.geometry.Transform3d transform)
    This method adds a transform to the detected target and returns the result 2D pose projected on the ground.
    static org.opencv.core.Rect
    getDetectedRect(org.opencv.core.Point[] corners)
    This method calculates the rectangle of the detected AprilTag.
    double
    This method returns the area of the detected object.
    This method returns the objects real world depth.
    This method returns the pose of the detected object relative to the camera.
    org.opencv.core.Rect
    This method returns the rect of the detected object.
    This method returns the objects real world width.
    This method returns the object's pixel height.
    This method returns the object's pixel width.
    This method returns the object's rotated rectangle angle.
    org.opencv.core.Point[]
    This method returns the rotated rect vertices of the detected object.
    This method returns the string form of the target info.

    Methods inherited from class java.lang.Object

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

    • timestamp

      public final double timestamp
    • target

      public final org.photonvision.targeting.PhotonTrackedTarget target
    • rect

      public final org.opencv.core.Rect rect
    • area

      public final double area
    • targetPose

      public final TrcPose2D targetPose
    • robotPose

      public final TrcPose2D robotPose
    • corners

      public final org.opencv.core.Point[] corners
    • pixelWidth

      public final double pixelWidth
    • pixelHeight

      public final double pixelHeight
    • rotatedAngle

      public final double rotatedAngle
  • Constructor Details

    • DetectedObject

      public DetectedObject(double timestamp, org.photonvision.targeting.PhotonTrackedTarget target, edu.wpi.first.math.geometry.Transform3d robotToCamera, TrcPose2D robotPose)
      Constructor: Creates an instance of the object.
      Parameters:
      timestamp - specifies the time stamp of the frame it was taken.
      target - specifies the photon detected target.
      robotToCamera - specifies the Transform3d of the camera position on the robot.
      robotPose - specifies the estimated robot pose.
  • Method Details

    • addTransformToTarget

      public TrcPose2D addTransformToTarget(org.photonvision.targeting.PhotonTrackedTarget target, edu.wpi.first.math.geometry.Transform3d robotToCam, edu.wpi.first.math.geometry.Transform3d transform)
      This method adds a transform to the detected target and returns the result 2D pose projected on the ground.
      Parameters:
      target - specifies the photon detected target object.
      robotToCam - specifies the Transform3d of the camera position on the robot.
      transform - specifies the transform to be added to the detected target.
      Returns:
      2D pose of the new target projected on the ground.
    • getDetectedRect

      public static org.opencv.core.Rect getDetectedRect(org.opencv.core.Point[] corners)
      This method calculates the rectangle of the detected AprilTag.
      Parameters:
      corners - specifies the corners of the MinAreaRect.
      Returns:
      AprilTag rectangle.
    • getObjectRect

      public org.opencv.core.Rect getObjectRect()
      This method returns the rect of the detected object.
      Specified by:
      getObjectRect in interface TrcVisionTargetInfo.ObjectInfo
      Returns:
      rect of the detected object.
    • getObjectArea

      public double getObjectArea()
      This method returns the area of the detected object.
      Specified by:
      getObjectArea in interface TrcVisionTargetInfo.ObjectInfo
      Returns:
      area of the detected object.
    • getPixelWidth

      public Double getPixelWidth()
      This method returns the object's pixel width.
      Specified by:
      getPixelWidth in interface TrcVisionTargetInfo.ObjectInfo
      Returns:
      object pixel width, null if not supported.
    • getPixelHeight

      public Double getPixelHeight()
      This method returns the object's pixel height.
      Specified by:
      getPixelHeight in interface TrcVisionTargetInfo.ObjectInfo
      Returns:
      object pixel height, null if not supported.
    • getRotatedAngle

      public Double getRotatedAngle()
      This method returns the object's rotated rectangle angle.
      Specified by:
      getRotatedAngle in interface TrcVisionTargetInfo.ObjectInfo
      Returns:
      rotated rectangle angle.
    • getObjectPose

      public TrcPose2D getObjectPose()
      This method returns the pose of the detected object relative to the camera.
      Specified by:
      getObjectPose in interface TrcVisionTargetInfo.ObjectInfo
      Returns:
      pose of the detected object relative to camera.
    • getObjectWidth

      public Double getObjectWidth()
      This method returns the objects real world width.
      Specified by:
      getObjectWidth in interface TrcVisionTargetInfo.ObjectInfo
      Returns:
      object real world width, null if not supported.
    • getObjectDepth

      public Double getObjectDepth()
      This method returns the objects real world depth.
      Specified by:
      getObjectDepth in interface TrcVisionTargetInfo.ObjectInfo
      Returns:
      object real world depth, null if not supported.
    • getRotatedRectVertices

      public org.opencv.core.Point[] getRotatedRectVertices()
      This method returns the rotated rect vertices of the detected object.
      Specified by:
      getRotatedRectVertices in interface TrcVisionTargetInfo.ObjectInfo
      Returns:
      rotated rect vertices.
    • toString

      public String toString()
      This method returns the string form of the target info.
      Overrides:
      toString in class Object
      Returns:
      string form of the target info.