Package frclib.vision
Class FrcOpenCvAprilTagPipeline.DetectedObject
java.lang.Object
trclib.vision.TrcOpenCvDetector.DetectedObject<edu.wpi.first.apriltag.AprilTagDetection>
frclib.vision.FrcOpenCvAprilTagPipeline.DetectedObject
- All Implemented Interfaces:
TrcVisionTargetInfo.ObjectInfo
- Enclosing class:
- FrcOpenCvAprilTagPipeline
public static class FrcOpenCvAprilTagPipeline.DetectedObject
extends TrcOpenCvDetector.DetectedObject<edu.wpi.first.apriltag.AprilTagDetection>
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
FieldsModifier and TypeFieldDescriptionfinal double
final double
final double
Fields inherited from class trclib.vision.TrcOpenCvDetector.DetectedObject
label, object
-
Constructor Summary
ConstructorsConstructorDescriptionDetectedObject
(String label, edu.wpi.first.apriltag.AprilTagDetection aprilTagInfo) Constructor: Creates an instance of the object. -
Method Summary
Modifier and TypeMethodDescriptionstatic org.opencv.core.Rect
getDetectedRect
(edu.wpi.first.apriltag.AprilTagDetection at) 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.toString()
This method returns the string form of the target info.
-
Field Details
-
pixelWidth
public final double pixelWidth -
pixelHeight
public final double pixelHeight -
rotatedAngle
public final double rotatedAngle
-
-
Constructor Details
-
DetectedObject
Constructor: Creates an instance of the object.- Parameters:
aprilTagInfo
- specifies the detected april tag info.
-
-
Method Details
-
getDetectedRect
public static org.opencv.core.Rect getDetectedRect(edu.wpi.first.apriltag.AprilTagDetection at) This method calculates the rectangle of the detected AprilTag.- Parameters:
at
- specifies the AprilTag info.- Returns:
- AprilTag rectangle.
-
getObjectRect
public org.opencv.core.Rect getObjectRect()This method returns the rect of the detected object.- Returns:
- rect of the detected object.
-
getObjectArea
public double getObjectArea()This method returns the area of the detected object.- Returns:
- area of the detected object.
-
getPixelWidth
This method returns the object's pixel width.- Returns:
- object pixel width, null if not supported.
-
getPixelHeight
This method returns the object's pixel height.- Returns:
- object pixel height, null if not supported.
-
getRotatedAngle
This method returns the object's rotated rectangle angle.- Returns:
- rotated rectangle angle.
-
getObjectPose
This method returns the pose of the detected object relative to the camera.- Returns:
- pose of the detected object relative to camera.
-
getObjectWidth
This method returns the objects real world width.- Returns:
- object real world width, null if not supported.
-
getObjectDepth
This method returns the objects real world depth.- 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.- Returns:
- rotated rect vertices.
-
toString
This method returns the string form of the target info.- Overrides:
toString
in classTrcOpenCvDetector.DetectedObject<edu.wpi.first.apriltag.AprilTagDetection>
- Returns:
- string form of the target info.
-