Package ftclib.vision

Class FtcLimelightVision

java.lang.Object
ftclib.vision.FtcLimelightVision

public class FtcLimelightVision extends Object
This class implements vision detection using Limelight 3A.
  • Field Details

    • moduleName

      private static final String moduleName
    • tracer

      public final TrcDbgTrace tracer
    • instanceName

      private final String instanceName
    • cameraPose

      private final TrcPose3D cameraPose
    • targetGroundOffset

      public final FtcLimelightVision.TargetGroundOffset targetGroundOffset
    • limelight

      public final com.qualcomm.hardware.limelightvision.Limelight3A limelight
    • pipelineIndex

      private int pipelineIndex
    • lastResultTimestamp

      private Double lastResultTimestamp
  • Constructor Details

    • FtcLimelightVision

      public FtcLimelightVision(com.qualcomm.robotcore.hardware.HardwareMap hardwareMap, String instanceName, TrcPose3D cameraPose, FtcLimelightVision.TargetGroundOffset targetGroundOffset)
      Constructor: Create an instance of the object.
      Parameters:
      hardwareMap - specifies the global hardware map.
      instanceName - specifies the Limelight camera name.
      cameraPose - specifies the camera position on the robot.
      targetGroundOffset - specifies the method to call to get target ground offset.
    • FtcLimelightVision

      public FtcLimelightVision(String instanceName, TrcPose3D cameraPose, FtcLimelightVision.TargetGroundOffset targetGroundOffset)
      Constructor: Create an instance of the object.
      Parameters:
      instanceName - specifies the Limelight camera name.
      cameraPose - specifies the camera position on the robot.
      targetGroundOffset - specifies the method to call to get the target ground offset.
  • Method Details

    • toString

      @NonNull public String toString()
      This method returns the camera name.
      Overrides:
      toString in class Object
      Returns:
      camera name.
    • setVisionEnabled

      public void setVisionEnabled(boolean enabled)
      This method starts/pauses vision processing.
      Parameters:
      enabled - specifies true to start vision processing, false to pause.
    • isVisionEnabled

      public boolean isVisionEnabled()
      This method checks if vision processing is enabled.
      Returns:
      true if vision processing is enabled, false otherwise.
    • setPipeline

      public boolean setPipeline(int index)
      This method sets the vision pipeline.
      Parameters:
      index - specifies the pipeline index to be set active.
      Returns:
      true if successful, false otherwise.
    • getPipeline

      public int getPipeline()
      This method returns the last set active pipeline.
      Returns:
      last set pipeline.
    • getDetectedObjects

      public ArrayList<FtcLimelightVision.DetectedObject> getDetectedObjects(FtcLimelightVision.ResultType resultType, String label, Double robotHeading)
      This method returns the array of detected objects.
      Parameters:
      resultType - specifies the result type to detect for.
      label - specifies the object label to look for, null if looking for any label.
      robotHeading - specifies robot heading in degrees, can be null if not provided.
      Returns:
      array list of detected objects.
    • getDetectedTargetInfo

      This method returns the target info of the given detected target.
      Parameters:
      target - specifies the detected target
      Returns:
      information about the detected target.
    • getDetectedTargetsInfo

      This method returns an array list of target info on the filtered detected targets.
      Parameters:
      resultType - specifies the result type to detect for.
      label - specifies the object label to look for, null if looking for any label.
      robotHeading - specifies robot heading in degrees, can be null if not provided.
      comparator - specifies the comparator to sort the array if provided, can be null if not provided.
      Returns:
      filtered target info array list.
    • getBestDetectedTargetInfo

      This method returns the target info of the best detected target.
      Parameters:
      resultType - specifies the result type to detect for.
      label - specifies the object label to look for, null if looking for any label.
      robotHeading - specifies robot heading in degrees, can be null if not provided.
      comparator - specifies the comparator to sort the array if provided, can be null if not provided.
      Returns:
      information about the best detected target.