Class LimelightSettings

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

public class LimelightSettings extends Object
Settings class to apply configurable options to the Limelight Sourced from Yet Another Limelight Lib(YALL)

These settings are sent from the roboRIO back to the Limelight to affect the LL.

One or more chains of ".withXXXX" methods can change the LL settings. The action of each ".withXXXX" method is essentially immediate, however, some slight delay is possible and the save() method will immediately save any settings that had not yet been saved.

Initially, at constructor time, settings are fetched from the LL, however, there is no provision to programatically access those values - they are dead, useless.

  • Constructor Details

  • Method Details

    • withLimelightLEDMode

      public LimelightSettings withLimelightLEDMode(LimelightSettings.LEDMode mode)
      Set the Limelight LimelightSettings.LEDMode.

      This method changes the Limelight - normally immediately.

      Parameters:
      mode - LimelightSettings.LEDMode enum
      Returns:
      LimelightSettings for chaining.
    • withPipelineIndex

      public LimelightSettings withPipelineIndex(int index)
      Set the current pipeline index for the Limelight

      This method changes the Limelight - normally immediately.

      Parameters:
      index - Pipeline index to use.
      Returns:
      LimelightSettings
    • withPriorityTagId

      public LimelightSettings withPriorityTagId(int aprilTagId)
      Set the Priority Tag ID for Limelight

      This method changes the Limelight - normally immediately.

      Parameters:
      aprilTagId - AprilTag ID to set as a priority.
      Returns:
      LimelightSettings for chaining.
    • withStreamMode

      public LimelightSettings withStreamMode(LimelightSettings.StreamMode mode)
      Set the Stream mode based on the LimelightSettings.StreamMode enum

      This method changes the Limelight - normally immediately.

      Parameters:
      mode - LimelightSettings.StreamMode to use.
      Returns:
      LimelightSettings for chaining.
    • withCropWindow

      public LimelightSettings withCropWindow(double minX, double maxX, double minY, double maxY)
      Sets the crop window for the camera. The crop window in the UI must be completely open.

      This method changes the Limelight - normally immediately.

      Parameters:
      minX - Minimum X value (-1 to 1)
      maxX - Maximum X value (-1 to 1)
      minY - Minimum Y value (-1 to 1)
      maxY - Maximum Y value (-1 to 1)
      Returns:
      LimelightSettings for chaining.
    • withImuMode

      public LimelightSettings withImuMode(LimelightSettings.ImuMode mode)
      Set the IMU Mode based on the LimelightSettings.ImuMode enum.

      This method changes the Limelight - normally immediately.

      Parameters:
      mode - LimelightSettings.ImuMode to use.
      Returns:
      LimelightSettings for chaining.
    • withImuAssistAlpha

      public LimelightSettings withImuAssistAlpha(double alpha)
      Set the IMU's alpha value for its complementary filter while in one of the LimelightSettings.ImuMode's assist modes.

      This method changes the Limelight - normally immediately.

      Parameters:
      alpha - Alpha value to set for the complementary filter. Default of 0.001.
      Returns:
      LimelightSettings for chaining.
    • withProcessedFrameFrequency

      public LimelightSettings withProcessedFrameFrequency(int skippedFrames)
      Sets the number of frames to skip between processing the contents of a frame.

      This method changes the Limelight - normally immediately.

      Parameters:
      skippedFrames - Number of frames to skip in between processing camera data.
      Returns:
      LimelightSettings for chaining.
    • withFiducialDownscalingOverride

      public LimelightSettings withFiducialDownscalingOverride(LimelightSettings.DownscalingOverride downscalingOverride)
      Sets the downscaling factor for AprilTag detection. Increasing downscale can improve performance at the cost of potentially reduced detection range.

      This method changes the Limelight - normally immediately.

      Parameters:
      downscalingOverride - Downscale factor. Valid values: 1.0 (no downscale), 1.5, 2.0, 3.0, 4.0. Set to 0 for pipeline control.
      Returns:
      LimelightSettings for chaining.
    • withAprilTagOffset

      public LimelightSettings withAprilTagOffset(Translation3d offset)
      Set the offset from the AprilTag that is of interest. More information here. Docs page

      This method changes the Limelight - normally immediately.

      Parameters:
      offset - Translation3d offset.
      Returns:
      LimelightSettings for chaining.
    • withArilTagIdFilter

      public LimelightSettings withArilTagIdFilter(List<Double> idFilter)
      Set the Limelight AprilTagID filter/override of which to track.

      This method changes the Limelight - normally immediately.

      Parameters:
      idFilter - Array of AprilTag ID's to track
      Returns:
      LimelightSettings for chaining.
    • withCameraOffset

      public LimelightSettings withCameraOffset(Pose3d offset)
      Set the Limelight offset.

      This method changes the Limelight - normally immediately.

      Parameters:
      offset - Pose3d of the Limelight with the Rotation3d set in Meters.
      Returns:
      LimelightSettings for chaining.
    • save

      public void save()
      Push any pending changes to the NetworkTable instance immediately.

      This method changes the Limelight immediately.

      Most setting changes are done essentially immediately and this method isn't needed but does no harm to assure changes.