Class LimelightSettings

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

public class LimelightSettings extends Object
Settings class to apply configurable options to the Limelight.

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 LED mode.
      Parameters:
      mode - LED mode to set.
      Returns:
      This object for method chaining.
      API Note:
      This method changes the Limelight - normally immediately.
    • withPipelineIndex

      public LimelightSettings withPipelineIndex(int index)
      Set the current pipeline index.
      Parameters:
      index - Pipeline index to use.
      Returns:
      This object for method chaining.
      API Note:
      This method changes the Limelight - normally immediately.
    • withPriorityTagId

      public LimelightSettings withPriorityTagId(int aprilTagId)
      Set the Priority Tag ID.
      Parameters:
      aprilTagId - AprilTag ID to set as a priority.
      Returns:
      This object for method chaining.
      API Note:
      This method changes the Limelight - normally immediately.
    • withStreamMode

      public LimelightSettings withStreamMode(LimelightSettings.StreamMode mode)
      Set the Stream mode.
      Parameters:
      mode - Stream mode to use.
      Returns:
      This object for method chaining.
      API Note:
      This method changes the Limelight - normally immediately.
    • 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.
      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:
      This object for method chaining.
      API Note:
      This method changes the Limelight - normally immediately.
    • withImuMode

      public LimelightSettings withImuMode(LimelightSettings.ImuMode mode)
      Set the IMU Mode.
      Parameters:
      mode - LimelightSettings.ImuMode to use.
      Returns:
      This object for method chaining.
      API Note:
      This method changes the Limelight - normally immediately.
    • 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.
      Parameters:
      alpha - Alpha value to set for the complementary filter. Default of 0.001.
      Returns:
      This object for method chaining.
      API Note:
      This method changes the Limelight - normally immediately.
    • withProcessedFrameFrequency

      public LimelightSettings withProcessedFrameFrequency(int skippedFrames)
      Sets the number of frames to skip between processing the contents of a frame.
      Parameters:
      skippedFrames - Number of frames to skip in between processing camera data.
      Returns:
      This object for method chaining.
      API Note:
      This method changes the Limelight - normally immediately.
    • 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.
      Parameters:
      downscalingOverride - Downscale factor.
      Returns:
      This object for method chaining.
      API Note:
      This method changes the Limelight - normally immediately.
    • withAprilTagOffset

      public LimelightSettings withAprilTagOffset(Translation3d offset)
      Set the offset from the AprilTag that is of interest. More information here. Docs page
      Parameters:
      offset - Translation3d offset.
      Returns:
      This object for method chaining.
      API Note:
      This method changes the Limelight - normally immediately.
    • withAprilTagIdFilter

      public LimelightSettings withAprilTagIdFilter(List<Integer> idFilter)
      Set the AprilTagID filter/override of which to track.
      Parameters:
      idFilter - Array of AprilTag ID's to track
      Returns:
      This object for method chaining.
      API Note:
      This method changes the Limelight - normally immediately.
    • withCameraOffset

      public LimelightSettings withCameraOffset(Pose3d offset)
      Set the camera position offset.
      Parameters:
      offset - Pose3d of the Limelight with the Rotation3d set in Meters.
      Returns:
      This object for method chaining.
      API Note:
      This method changes the Limelight - normally immediately.
    • save

      public void save()
      Push any pending changes to the NetworkTable instance immediately.
      API Note:
      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.