Class LimelightSettings
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 aLimelightSettingsobject with all configurable features of aLimelight. -
Method Summary
Modifier and TypeMethodDescriptionvoidsave()Push any pending changes to theNetworkTableinstance immediately.withAprilTagOffset(Translation3d offset) Set the offset from the AprilTag that is of interest.withArilTagIdFilter(List<Double> idFilter) Set theLimelightAprilTagID filter/override of which to track.withCameraOffset(Pose3d offset) Set theLimelightoffset.withCropWindow(double minX, double maxX, double minY, double maxY) Sets the crop window for the camera.withFiducialDownscalingOverride(LimelightSettings.DownscalingOverride downscalingOverride) Sets the downscaling factor for AprilTag detection.Set the IMU Mode based on theLimelightSettings.ImuModeenum.Set theLimelightLimelightSettings.LEDMode.withPipelineIndex(int index) Set the current pipeline index for theLimelightwithPriorityTagId(int aprilTagId) Set the Priority Tag ID forLimelightwithRobotOrientation(Orientation3d orientation) Set the current robotOrientation3d(normally given by the robot gyro) for LL to use in its MegaTag2 determination.Set the Stream mode based on theLimelightSettings.StreamModeenum
-
Constructor Details
-
LimelightSettings
Create aLimelightSettingsobject with all configurable features of aLimelight.- Parameters:
camera-Limelightto use.
-
-
Method Details
-
withLimelightLEDMode
Set theLimelightLimelightSettings.LEDMode.This method changes the Limelight - normally immediately.
- Parameters:
mode-LimelightSettings.LEDModeenum- Returns:
LimelightSettingsfor chaining.
-
withPipelineIndex
Set the current pipeline index for theLimelightThis method changes the Limelight - normally immediately.
- Parameters:
index- Pipeline index to use.- Returns:
LimelightSettings
-
withPriorityTagId
Set the Priority Tag ID forLimelightThis method changes the Limelight - normally immediately.
- Parameters:
aprilTagId- AprilTag ID to set as a priority.- Returns:
LimelightSettingsfor chaining.
-
withStreamMode
Set the Stream mode based on theLimelightSettings.StreamModeenumThis method changes the Limelight - normally immediately.
- Parameters:
mode-LimelightSettings.StreamModeto use.- Returns:
LimelightSettingsfor chaining.
-
withCropWindow
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:
LimelightSettingsfor chaining.
-
withImuMode
Set the IMU Mode based on theLimelightSettings.ImuModeenum.This method changes the Limelight - normally immediately.
- Parameters:
mode-LimelightSettings.ImuModeto use.- Returns:
LimelightSettingsfor chaining.
-
withRobotOrientation
Set the current robotOrientation3d(normally given by the robot gyro) for LL to use in its MegaTag2 determination.This method changes the Limelight - normally immediately.
- Parameters:
orientation-Orientation3dobject to set the current orientation to.- Returns:
LimelightSettingsfor 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:
LimelightSettingsfor chaining.
-
withAprilTagOffset
Set the offset from the AprilTag that is of interest. More information here. Docs pageThis method changes the Limelight - normally immediately.
- Parameters:
offset-Translation3doffset.- Returns:
LimelightSettingsfor chaining.
-
withArilTagIdFilter
Set theLimelightAprilTagID filter/override of which to track.This method changes the Limelight - normally immediately.
- Parameters:
idFilter- Array of AprilTag ID's to track- Returns:
LimelightSettingsfor chaining.
-
withCameraOffset
Set theLimelightoffset.This method changes the Limelight - normally immediately.
- Parameters:
offset-Pose3dof theLimelightwith theRotation3dset in Meters.- Returns:
LimelightSettingsfor chaining.
-
save
public void save()Push any pending changes to theNetworkTableinstance 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.
-