Class BaseLimeLight
- java.lang.Object
-
- io.github.frc5024.lib5k.hardware.limelightvision.BaseLimeLight
-
- All Implemented Interfaces:
Sendable
- Direct Known Subclasses:
LimeLight1
,LimeLight2
public abstract class BaseLimeLight extends java.lang.Object implements Sendable
The base for interaction with LimeLight products. Following this specification: https://docs.limelightvision.io/en/latest/networktables_api.html
-
-
Constructor Summary
Constructors Constructor Description BaseLimeLight(NetworkTable remoteTable, java.lang.String ipAddress, double maxXAngleDegrees, double maxYAngleDegrees)
Create a BaseLimeLight
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description void
enableSnapshots(boolean enabled)
Set if the camera should be saving a frame once every 2 seconds to internal storage.int
getActivePipelineID()
Get the ID of the currently active image processing pipeline on-devicedouble
getImageProcessingLatencyMS()
Get the number of MS of latency the camera takes to process an imageHyperbolicAxisAlignedBoundingBox
getTargetBoundsOrNull()
Get the bounding box for the LimeLight target, or NULL if no target is foundboolean
hasTarget()
Check if the LimeLight can see its targetvoid
initSendable(SendableBuilder builder)
void
portForwardCameraStream(int localPort)
Port-forward the camera stream through the RoboRIOvoid
setActivePipeline(int id)
Switch to a new image processing pipelinevoid
setLEDMode(LimeLightLEDMode mode)
Set the LimeLight LED modevoid
setOperationMode(LimeLightOperationMode mode)
Set the camera operation modevoid
setStreamMode(LimeLightStreamMode mode)
Set the streaming mode-
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
-
Methods inherited from interface edu.wpi.first.wpilibj.Sendable
addChild, getName, getSubsystem, setName, setName, setName, setName, setSubsystem
-
-
-
-
Constructor Detail
-
BaseLimeLight
public BaseLimeLight(NetworkTable remoteTable, java.lang.String ipAddress, double maxXAngleDegrees, double maxYAngleDegrees)
Create a BaseLimeLight- Parameters:
remoteTable
- Device NT tableipAddress
- Device IP addressmaxXAngleDegrees
- Maximum X angle of the camera lensemaxYAngleDegrees
- Maximum Y angle of the camera lense
-
-
Method Detail
-
portForwardCameraStream
public void portForwardCameraStream(int localPort)
Port-forward the camera stream through the RoboRIO- Parameters:
localPort
- RoboRIO port to forward through
-
hasTarget
public boolean hasTarget()
Check if the LimeLight can see its target- Returns:
- Can see target?
-
getTargetBoundsOrNull
@CheckForNull public HyperbolicAxisAlignedBoundingBox getTargetBoundsOrNull()
Get the bounding box for the LimeLight target, or NULL if no target is found- Returns:
- HyperbolicAxisAlignedBoundingBox or NULL
-
getImageProcessingLatencyMS
public double getImageProcessingLatencyMS()
Get the number of MS of latency the camera takes to process an image- Returns:
- Latency in MS
-
getActivePipelineID
public int getActivePipelineID()
Get the ID of the currently active image processing pipeline on-device- Returns:
- Current image pipeline ID
-
setActivePipeline
public void setActivePipeline(int id)
Switch to a new image processing pipeline- Parameters:
id
- Pipeline ID
-
setLEDMode
public void setLEDMode(LimeLightLEDMode mode)
Set the LimeLight LED mode- Parameters:
mode
- LED mode
-
setOperationMode
public void setOperationMode(LimeLightOperationMode mode)
Set the camera operation mode- Parameters:
mode
- Operation mode
-
setStreamMode
public void setStreamMode(LimeLightStreamMode mode)
Set the streaming mode- Parameters:
mode
- Streaming mode
-
enableSnapshots
public void enableSnapshots(boolean enabled)
Set if the camera should be saving a frame once every 2 seconds to internal storage. Useful for critical gameplay review- Parameters:
enabled
- Enable snapshots
-
initSendable
public void initSendable(SendableBuilder builder)
- Specified by:
initSendable
in interfaceSendable
-
-