Class LimelightSettings
java.lang.Object
io.github.roboblazers7617.limelight.LimelightSettings
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.
-
Nested Class Summary
Nested Classes -
Constructor Summary
ConstructorsConstructorDescriptionLimelightSettings
(Limelight camera) Create aLimelightSettings
object with all configurable features of aLimelight
. -
Method Summary
Modifier and TypeMethodDescriptionvoid
save()
Push any pending changes to theNetworkTable
instance immediately.withAprilTagIdFilter
(List<Integer> idFilter) Set theAprilTagID filter/override
of which to track.withAprilTagOffset
(Translation3d offset) Set theoffset
from the AprilTag that is of interest.withCameraOffset
(Pose3d offset) Set thecamera position offset
.withCropWindow
(double minX, double maxX, double minY, double maxY) Sets the crop window for the camera.withFiducialDownscalingOverride
(LimelightSettings.DownscalingOverride downscalingOverride) Sets thedownscaling factor
for AprilTag detection.withImuAssistAlpha
(double alpha) Set theIMU's alpha value
for its complementary filter while in one of theLimelightSettings.ImuMode
's assist modes.Set theIMU Mode
.Set theLED mode
.withPipelineIndex
(int index) Set thecurrent pipeline index
.withPriorityTagId
(int aprilTagId) Set thePriority Tag ID
.withProcessedFrameFrequency
(int skippedFrames) Sets thenumber of frames to skip
between processing the contents of a frame.Set theStream mode
.
-
Constructor Details
-
LimelightSettings
Create aLimelightSettings
object with all configurable features of aLimelight
.- Parameters:
camera
-Limelight
to use.
-
-
Method Details
-
withLimelightLEDMode
Set theLED mode
.- Parameters:
mode
- LED mode to set.- Returns:
- This object for method chaining.
- API Note:
- This method changes the Limelight - normally immediately.
-
withPipelineIndex
Set thecurrent pipeline index
.- Parameters:
index
- Pipeline index to use.- Returns:
- This object for method chaining.
- API Note:
- This method changes the Limelight - normally immediately.
-
withPriorityTagId
Set thePriority 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
Set theStream mode
.- Parameters:
mode
- Stream mode to use.- Returns:
- This object for method chaining.
- API Note:
- This method changes the Limelight - normally immediately.
-
withCropWindow
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
Set theIMU Mode
.- Parameters:
mode
-LimelightSettings.ImuMode
to use.- Returns:
- This object for method chaining.
- API Note:
- This method changes the Limelight - normally immediately.
-
withImuAssistAlpha
Set theIMU's alpha value
for its complementary filter while in one of theLimelightSettings.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
Sets thenumber 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 thedownscaling 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
Set theoffset
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
Set theAprilTagID 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
Set thecamera position offset
.- Parameters:
offset
-Pose3d
of theLimelight
with theRotation3d
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 theNetworkTable
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.
-