Class PipelineDataCollator

java.lang.Object
io.github.roboblazers7617.limelight.PipelineDataCollator

public class PipelineDataCollator extends Object
Fetches pipeline data from a Limelight.
  • Constructor Details

    • PipelineDataCollator

      public PipelineDataCollator(Limelight limelight)
      Creates a new PipelineDataCollator.
      Parameters:
      limelight - The Limelight to get data from.
  • Method Details

    • getRawDetections

      public RawDetection[] getRawDetections()
      Gets the latest raw neural detector results from NetworkTables name.
      Returns:
      Array of RawDetection objects containing detection details.
    • getRawFiducialTargets

      public RawFiducialTarget[] getRawFiducialTargets()
      Gets the latest raw fiducial/AprilTag detection results from NetworkTables.
      Returns:
      Array of RawFiducialTarget objects containing detection details.
    • getLatestResults

      public PipelineResult getLatestResults(boolean showParseTime)
      Gets the latest JSON results output and returns a LimelightResults object.
      Parameters:
      showParseTime - Print out the parse time to standard output.
      Returns:
      LimelightResults object containing all current target data
    • getTV

      public boolean getTV()
      Does the Limelight have a valid target?
      Returns:
      True if a valid target is present, false otherwise.
    • getTX

      public double getTX()
      Gets the horizontal offset from the crosshair to the target in degrees.
      Returns:
      Horizontal offset angle in degrees.
    • getTY

      public double getTY()
      Gets the vertical offset from the crosshair to the target in degrees.
      Returns:
      Vertical offset angle in degrees.
    • getTXNC

      public double getTXNC()
      Gets the horizontal offset from the principal pixel/point to the target in degrees. This is the most accurate 2d metric if you are using a calibrated camera and you don't need adjustable crosshair functionality.
      Returns:
      Horizontal offset angle in degrees
    • getTYNC

      public double getTYNC()
      Gets the vertical offset from the principal pixel/point to the target in degrees. This is the most accurate 2d metric if you are using a calibrated camera and you don't need adjustable crosshair functionality.
      Returns:
      Vertical offset angle in degrees
    • getTA

      public double getTA()
      Gets the target area as a percentage of the image (0-100%).
      Returns:
      Target area percentage (0-100).
    • getT2DArray

      public double[] getT2DArray()
      T2D is an array that contains several targeting metrics.
      Returns:
      Array containing [targetValid, targetCount, targetLatency, captureLatency, tx, ty, txnc, tync, ta, tid, targetClassIndexDetector, targetClassIndexClassifier, targetLongSidePixels, targetShortSidePixels, targetHorizontalExtentPixels, targetVerticalExtentPixels, targetSkewDegrees]
    • getTargetCount

      public int getTargetCount()
      Gets the number of targets currently detected.
      Returns:
      Number of detected targets
    • getClassifierClassIndex

      public int getClassifierClassIndex()
      Gets the classifier class index from the currently running neural classifier pipeline.
      Returns:
      Class index from classifier pipeline.
    • getDetectorClassIndex

      public int getDetectorClassIndex()
      Gets the detector class index from the primary result of the currently running neural detector pipeline.
      Returns:
      Class index from detector pipeline.
    • getClassifierClass

      public String getClassifierClass()
      Gets the current neural classifier result class name.
      Returns:
      Class name string from classifier pipeline.
    • getDetectorClass

      public String getDetectorClass()
      Gets the primary neural detector result class name.
      Returns:
      Class name string from detector pipeline.
    • getLatency_Pipeline

      public double getLatency_Pipeline()
      Gets the pipeline's processing latency contribution.
      Returns:
      Pipeline latency in milliseconds.
    • getLatency_Capture

      public double getLatency_Capture()
      Gets the capture latency.
      Returns:
      Capture latency in milliseconds.
    • getCurrentPipelineIndex

      public double getCurrentPipelineIndex()
      Gets the active pipeline index.
      Returns:
      Current pipeline index (0-9).
    • getCurrentPipelineType

      public String getCurrentPipelineType()
      Gets the current pipeline type.
      Returns:
      Pipeline type string (e.g. "retro", "apriltag", etc).
    • getJSONDump

      public String getJSONDump()
      Gets the full JSON results dump.
      Returns:
      JSON string containing all current results.
    • getBotPose3d_TargetSpace

      public Pose3d getBotPose3d_TargetSpace()
      Gets the robot's 3D pose with respect to the currently tracked target's coordinate system.
      Returns:
      Pose3d object representing the robot's position and orientation relative to the target.
    • getCameraPose3d_TargetSpace

      public Pose3d getCameraPose3d_TargetSpace()
      Gets the camera's 3D pose with respect to the currently tracked target's coordinate system.
      Returns:
      Pose3d object representing the camera's position and orientation relative to the target.
    • getTargetPose3d_CameraSpace

      public Pose3d getTargetPose3d_CameraSpace()
      Gets the target's 3D pose with respect to the camera's coordinate system.
      Returns:
      Pose3d object representing the target's position and orientation relative to the camera.
    • getTargetPose3d_RobotSpace

      public Pose3d getTargetPose3d_RobotSpace()
      Gets the target's 3D pose with respect to the robot's coordinate system.
      Returns:
      Pose3d object representing the target's position and orientation relative to the robot.
    • getCameraPose3d_RobotSpace

      public Pose3d getCameraPose3d_RobotSpace()
      Gets the camera's 3D pose with respect to the robot's coordinate system.
      Returns:
      Pose3d object representing the camera's position and orientation relative to the robot.
    • getStandardDeviationsArray

      public double[] getStandardDeviationsArray()
      Gets the standard deviation readings as an array.
      Returns:
      Array containing standard deviations for vision measurements.
      API Note:
      Array format documented in the standardDeviationsEntry Javadoc. Also, some details about where (not) to use this data can be found there.
    • getTargetColor

      public double[] getTargetColor()
      Gets the color of the target.
      Returns:
      Color in the format [H, S, V].
    • getFiducialID

      public double getFiducialID()
      Gets the ID of the primary AprilTag.
      Returns:
      AprilTag ID.
    • getNeuralClassID

      public String getNeuralClassID()
      Gets the class ID of the primary neural detector/classifier result.
      Returns:
      Class ID.
    • getRawBarcodeData

      public String[] getRawBarcodeData()
      Gets the raw barcode results.
      Returns:
      String array of barcode data.
    • getHardwareMetrics

      public double[] getHardwareMetrics()
      Gets the raw hardware metrics array.
      Returns:
      Double array containing hardware metrics.
      API Note:
      Array format documented under hardwareMetricsEntry.
    • getCpuTemperature

      public double getCpuTemperature()
      Gets the CPU temperature from the hardwareMetricsEntry.
      Returns:
      Current CPU temperature (Celcius).
    • getCpuUsage

      public double getCpuUsage()
      Gets the CPU usage from the hardwareMetricsEntry.
      Returns:
      Current CPU usage (percentage).
    • getRamUsage

      public double getRamUsage()
      Gets the RAM usage from the hardwareMetricsEntry.
      Returns:
      Current RAM usage (percentage).
    • getFps

      public double getFps()
      Gets the FPS from the hardwareMetricsEntry.
      Returns:
      Current pipeline FPS.