Package frc.robot
Class LimelightHelpers
java.lang.Object
frc.robot.LimelightHelpers
LimelightHelpers provides static methods and classes for interfacing with Limelight vision cameras in FRC.
This library supports all Limelight features including AprilTag tracking, Neural Networks, and standard color/retroreflective tracking.
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic class
Encapsulates the state of an internal Limelight IMU.static class
Limelight Results object, parsed from a Limelight's JSON results output.static class
Represents a Barcode Target Result extracted from JSON Outputstatic class
Represents a Neural Classifier Pipeline Result extracted from JSON Outputstatic class
Represents a Neural Detector Pipeline Result extracted from JSON Outputstatic class
Represents an AprilTag/Fiducial Target Result extracted from JSON Outputstatic class
Represents a Color/Retroreflective Target Result extracted from JSON Outputstatic class
Represents a 3D Pose Estimate.static class
Represents a Limelight Raw Neural Detector result from Limelight's NetworkTables output.static class
Represents a Limelight Raw Fiducial result from Limelight's NetworkTables output. -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionstatic void
Flush()
static double[]
getBotpose
(String limelightName) Deprecated.static double[]
getBotPose
(String limelightName) static double[]
getBotPose_TargetSpace
(String limelightName) static double[]
getBotpose_wpiBlue
(String limelightName) Deprecated.static double[]
getBotPose_wpiBlue
(String limelightName) static double[]
getBotpose_wpiRed
(String limelightName) Deprecated.static double[]
getBotPose_wpiRed
(String limelightName) static Pose2d
getBotPose2d
(String limelightName) Gets the Pose2d for easy use with Odometry vision pose estimator (addVisionMeasurement)static Pose2d
getBotPose2d_wpiBlue
(String limelightName) Gets the Pose2d for easy use with Odometry vision pose estimator (addVisionMeasurement)static Pose2d
getBotPose2d_wpiRed
(String limelightName) Gets the Pose2d for easy use with Odometry vision pose estimator (addVisionMeasurement)static Pose3d
getBotPose3d
(String limelightName) static Pose3d
getBotPose3d_TargetSpace
(String limelightName) Gets the robot's 3D pose with respect to the currently tracked target's coordinate system.static Pose3d
getBotPose3d_wpiBlue
(String limelightName) (Recommended) Gets the robot's 3D pose in the WPILib Blue Alliance Coordinate System.static Pose3d
getBotPose3d_wpiRed
(String limelightName) (Not Recommended) Gets the robot's 3D pose in the WPILib Red Alliance Coordinate System.getBotPoseEstimate_wpiBlue
(String limelightName) Gets the MegaTag1 Pose2d and timestamp for use with WPILib pose estimator (addVisionMeasurement) in the WPILib Blue alliance coordinate system.getBotPoseEstimate_wpiBlue_MegaTag2
(String limelightName) Gets the MegaTag2 Pose2d and timestamp for use with WPILib pose estimator (addVisionMeasurement) in the WPILib Blue alliance coordinate system.getBotPoseEstimate_wpiRed
(String limelightName) Gets the Pose2d and timestamp for use with WPILib pose estimator (addVisionMeasurement) when you are on the RED alliancegetBotPoseEstimate_wpiRed_MegaTag2
(String limelightName) Gets the Pose2d and timestamp for use with WPILib pose estimator (addVisionMeasurement) when you are on the RED alliancestatic double[]
getCameraPose_TargetSpace
(String limelightName) static Pose3d
getCameraPose3d_RobotSpace
(String limelightName) Gets the camera's 3D pose with respect to the robot's coordinate system.static Pose3d
getCameraPose3d_TargetSpace
(String limelightName) Gets the camera's 3D pose with respect to the currently tracked target's coordinate system.static String
getClassifierClass
(String limelightName) Gets the current neural classifier result class name.static int
getClassifierClassIndex
(String limelightName) Gets the classifier class index from the currently running neural classifier pipelinestatic double
getCurrentPipelineIndex
(String limelightName) Gets the active pipeline index.static String
getCurrentPipelineType
(String limelightName) Gets the current pipeline type.static String
getDetectorClass
(String limelightName) Gets the primary neural detector result class name.static int
getDetectorClassIndex
(String limelightName) Gets the detector class index from the primary result of the currently running neural detector pipeline.static double
getFiducialID
(String limelightName) static LimelightHelpers.IMUData
getIMUData
(String limelightName) Gets the current IMU data from NetworkTables.static String
getJSONDump
(String limelightName) Gets the full JSON results dump.static double
getLatency_Capture
(String limelightName) Gets the capture latency.static double
getLatency_Pipeline
(String limelightName) Gets the pipeline's processing latency contribution.getLatestResults
(String limelightName) Gets the latest JSON results output and returns a LimelightResults object.static DoubleArrayEntry
getLimelightDoubleArrayEntry
(String tableName, String entryName) static double
getLimelightNTDouble
(String tableName, String entryName) static double[]
getLimelightNTDoubleArray
(String tableName, String entryName) static String
getLimelightNTString
(String tableName, String entryName) static String[]
getLimelightNTStringArray
(String tableName, String entryName) static NetworkTable
getLimelightNTTable
(String tableName) static NetworkTableEntry
getLimelightNTTableEntry
(String tableName, String entryName) static URL
getLimelightURLString
(String tableName, String request) static String
getNeuralClassID
(String limelightName) static double[]
getPythonScriptData
(String limelightName) static String[]
getRawBarcodeData
(String limelightName) static LimelightHelpers.RawDetection[]
getRawDetections
(String limelightName) Gets the latest raw neural detector results from NetworkTablesstatic LimelightHelpers.RawFiducial[]
getRawFiducials
(String limelightName) Gets the latest raw fiducial/AprilTag detection results from NetworkTables.static double[]
getT2DArray
(String limelightName) T2D is an array that contains several targeting metrcisstatic double
Gets the target area as a percentage of the image (0-100%).static double[]
getTargetColor
(String limelightName) static int
getTargetCount
(String limelightName) Gets the number of targets currently detected.static double[]
getTargetPose_CameraSpace
(String limelightName) static double[]
getTargetPose_RobotSpace
(String limelightName) static Pose3d
getTargetPose3d_CameraSpace
(String limelightName) Gets the target's 3D pose with respect to the camera's coordinate system.static Pose3d
getTargetPose3d_RobotSpace
(String limelightName) Gets the target's 3D pose with respect to the robot's coordinate system.static boolean
Does the Limelight have a valid target?static double
Gets the horizontal offset from the crosshair to the target in degrees.static double
Gets the horizontal offset from the principal pixel/point to the target in degrees.static double
Gets the vertical offset from the crosshair to the target in degrees.static double
Gets the vertical offset from the principal pixel/point to the target in degrees.static double[]
pose2dToArray
(Pose2d pose) Converts a Pose2d object to an array of doubles in the format [x, y, z, roll, pitch, yaw].static double[]
pose3dToArray
(Pose3d pose) Converts a Pose3d object to an array of doubles in the format [x, y, z, roll, pitch, yaw].static void
Prints detailed information about a PoseEstimate to standard output.static void
setCameraPose_RobotSpace
(String limelightName, double forward, double side, double up, double roll, double pitch, double yaw) Sets the camera pose relative to the robot.static void
setCropWindow
(String limelightName, double cropXMin, double cropXMax, double cropYMin, double cropYMax) Sets the crop window for the camera.static void
SetFidcuial3DOffset
(String limelightName, double x, double y, double z) Sets the 3D point-of-interest offset for the current fiducial pipeline.static void
setFiducial3DOffset
(String limelightName, double offsetX, double offsetY, double offsetZ) Sets 3D offset point for easy 3D targeting.static void
SetFiducialDownscalingOverride
(String limelightName, float downscale) Sets the downscaling factor for AprilTag detection.static void
SetFiducialIDFiltersOverride
(String limelightName, int[] validIDs) Overrides the valid AprilTag IDs that will be used for localization.static void
SetIMUMode
(String limelightName, int mode) Configures the IMU mode for MegaTag2 Localizationstatic void
setLEDMode_ForceBlink
(String limelightName) static void
setLEDMode_ForceOff
(String limelightName) static void
setLEDMode_ForceOn
(String limelightName) static void
setLEDMode_PipelineControl
(String limelightName) Sets LED mode to be controlled by the current pipeline.static void
setLimelightNTDouble
(String tableName, String entryName, double val) static void
setLimelightNTDoubleArray
(String tableName, String entryName, double[] val) static void
setPipelineIndex
(String limelightName, int pipelineIndex) static void
setPriorityTagID
(String limelightName, int ID) static void
setPythonScriptData
(String limelightName, double[] outgoingPythonData) static void
SetRobotOrientation
(String limelightName, double yaw, double yawRate, double pitch, double pitchRate, double roll, double rollRate) Sets robot orientation values used by MegaTag2 localization algorithm.static void
SetRobotOrientation_NoFlush
(String limelightName, double yaw, double yawRate, double pitch, double pitchRate, double roll, double rollRate) static void
setStreamMode_PiPMain
(String limelightName) Enables Picture-in-Picture mode with secondary stream in the corner.static void
setStreamMode_PiPSecondary
(String limelightName) Enables Picture-in-Picture mode with primary stream in the corner.static void
setStreamMode_Standard
(String limelightName) Enables standard side-by-side stream mode.static CompletableFuture<Boolean>
takeSnapshot
(String tableName, String snapshotName) Asynchronously take snapshot.static Pose2d
toPose2D
(double[] inData) Takes a 6-length array of pose data and converts it to a Pose2d object.static Pose3d
toPose3D
(double[] inData) Takes a 6-length array of pose data and converts it to a Pose3d object.static Boolean
-
Constructor Details
-
LimelightHelpers
public LimelightHelpers()
-
-
Method Details
-
toPose3D
public static Pose3d toPose3D(double[] inData) Takes a 6-length array of pose data and converts it to a Pose3d object. Array format: [x, y, z, roll, pitch, yaw] where angles are in degrees.- Parameters:
inData
- Array containing pose data [x, y, z, roll, pitch, yaw]- Returns:
- Pose3d object representing the pose, or empty Pose3d if invalid data
-
toPose2D
public static Pose2d toPose2D(double[] inData) Takes a 6-length array of pose data and converts it to a Pose2d object. Uses only x, y, and yaw components, ignoring z, roll, and pitch. Array format: [x, y, z, roll, pitch, yaw] where angles are in degrees.- Parameters:
inData
- Array containing pose data [x, y, z, roll, pitch, yaw]- Returns:
- Pose2d object representing the pose, or empty Pose2d if invalid data
-
pose3dToArray
public static double[] pose3dToArray(Pose3d pose) Converts a Pose3d object to an array of doubles in the format [x, y, z, roll, pitch, yaw]. Translation components are in meters, rotation components are in degrees.- Parameters:
pose
- The Pose3d object to convert- Returns:
- A 6-element array containing [x, y, z, roll, pitch, yaw]
-
pose2dToArray
public static double[] pose2dToArray(Pose2d pose) Converts a Pose2d object to an array of doubles in the format [x, y, z, roll, pitch, yaw]. Translation components are in meters, rotation components are in degrees. Note: z, roll, and pitch will be 0 since Pose2d only contains x, y, and yaw.- Parameters:
pose
- The Pose2d object to convert- Returns:
- A 6-element array containing [x, y, 0, 0, 0, yaw]
-
getRawFiducials
Gets the latest raw fiducial/AprilTag detection results from NetworkTables.- Parameters:
limelightName
- Name/identifier of the Limelight- Returns:
- Array of RawFiducial objects containing detection details
-
getRawDetections
Gets the latest raw neural detector results from NetworkTables- Parameters:
limelightName
- Name/identifier of the Limelight- Returns:
- Array of RawDetection objects containing detection details
-
printPoseEstimate
Prints detailed information about a PoseEstimate to standard output. Includes timestamp, latency, tag count, tag span, average tag distance, average tag area, and detailed information about each detected fiducial.- Parameters:
pose
- The PoseEstimate object to print. If null, prints "No PoseEstimate available."
-
validPoseEstimate
-
getLimelightNTTable
-
Flush
public static void Flush() -
getLimelightNTTableEntry
-
getLimelightDoubleArrayEntry
-
getLimelightNTDouble
-
setLimelightNTDouble
-
setLimelightNTDoubleArray
-
getLimelightNTDoubleArray
-
getLimelightNTString
-
getLimelightNTStringArray
-
getLimelightURLString
-
getTV
Does the Limelight have a valid target?- Parameters:
limelightName
- Name of the Limelight camera ("" for default)- Returns:
- True if a valid target is present, false otherwise
-
getTX
Gets the horizontal offset from the crosshair to the target in degrees.- Parameters:
limelightName
- Name of the Limelight camera ("" for default)- Returns:
- Horizontal offset angle in degrees
-
getTY
Gets the vertical offset from the crosshair to the target in degrees.- Parameters:
limelightName
- Name of the Limelight camera ("" for default)- Returns:
- Vertical offset angle in degrees
-
getTXNC
Gets the horizontal offset from the principal pixel/point to the target in degrees. This is the most accurate 2d metric if you are using a calibrated camera and you don't need adjustable crosshair functionality.- Parameters:
limelightName
- Name of the Limelight camera ("" for default)- Returns:
- Horizontal offset angle in degrees
-
getTYNC
Gets the vertical offset from the principal pixel/point to the target in degrees. This is the most accurate 2d metric if you are using a calibrated camera and you don't need adjustable crosshair functionality.- Parameters:
limelightName
- Name of the Limelight camera ("" for default)- Returns:
- Vertical offset angle in degrees
-
getTA
Gets the target area as a percentage of the image (0-100%).- Parameters:
limelightName
- Name of the Limelight camera ("" for default)- Returns:
- Target area percentage (0-100)
-
getT2DArray
T2D is an array that contains several targeting metrcis- Parameters:
limelightName
- Name of the Limelight camera- Returns:
- Array containing [targetValid, targetCount, targetLatency, captureLatency, tx, ty, txnc, tync, ta, tid, targetClassIndexDetector, targetClassIndexClassifier, targetLongSidePixels, targetShortSidePixels, targetHorizontalExtentPixels, targetVerticalExtentPixels, targetSkewDegrees]
-
getTargetCount
Gets the number of targets currently detected.- Parameters:
limelightName
- Name of the Limelight camera- Returns:
- Number of detected targets
-
getClassifierClassIndex
Gets the classifier class index from the currently running neural classifier pipeline- Parameters:
limelightName
- Name of the Limelight camera- Returns:
- Class index from classifier pipeline
-
getDetectorClassIndex
Gets the detector class index from the primary result of the currently running neural detector pipeline.- Parameters:
limelightName
- Name of the Limelight camera- Returns:
- Class index from detector pipeline
-
getClassifierClass
Gets the current neural classifier result class name.- Parameters:
limelightName
- Name of the Limelight camera- Returns:
- Class name string from classifier pipeline
-
getDetectorClass
Gets the primary neural detector result class name.- Parameters:
limelightName
- Name of the Limelight camera- Returns:
- Class name string from detector pipeline
-
getLatency_Pipeline
Gets the pipeline's processing latency contribution.- Parameters:
limelightName
- Name of the Limelight camera- Returns:
- Pipeline latency in milliseconds
-
getLatency_Capture
Gets the capture latency.- Parameters:
limelightName
- Name of the Limelight camera- Returns:
- Capture latency in milliseconds
-
getCurrentPipelineIndex
Gets the active pipeline index.- Parameters:
limelightName
- Name of the Limelight camera- Returns:
- Current pipeline index (0-9)
-
getCurrentPipelineType
Gets the current pipeline type.- Parameters:
limelightName
- Name of the Limelight camera- Returns:
- Pipeline type string (e.g. "retro", "apriltag", etc)
-
getJSONDump
Gets the full JSON results dump.- Parameters:
limelightName
- Name of the Limelight camera- Returns:
- JSON string containing all current results
-
getBotpose
Deprecated.Switch to getBotPose- Parameters:
limelightName
-- Returns:
-
getBotpose_wpiRed
Deprecated.Switch to getBotPose_wpiRed- Parameters:
limelightName
-- Returns:
-
getBotpose_wpiBlue
Deprecated.Switch to getBotPose_wpiBlue- Parameters:
limelightName
-- Returns:
-
getBotPose
-
getBotPose_wpiRed
-
getBotPose_wpiBlue
-
getBotPose_TargetSpace
-
getCameraPose_TargetSpace
-
getTargetPose_CameraSpace
-
getTargetPose_RobotSpace
-
getTargetColor
-
getFiducialID
-
getNeuralClassID
-
getRawBarcodeData
-
getBotPose3d
-
getBotPose3d_wpiRed
(Not Recommended) Gets the robot's 3D pose in the WPILib Red Alliance Coordinate System.- Parameters:
limelightName
- Name/identifier of the Limelight- Returns:
- Pose3d object representing the robot's position and orientation in Red Alliance field space
-
getBotPose3d_wpiBlue
(Recommended) Gets the robot's 3D pose in the WPILib Blue Alliance Coordinate System.- Parameters:
limelightName
- Name/identifier of the Limelight- Returns:
- Pose3d object representing the robot's position and orientation in Blue Alliance field space
-
getBotPose3d_TargetSpace
Gets the robot's 3D pose with respect to the currently tracked target's coordinate system.- Parameters:
limelightName
- Name/identifier of the Limelight- Returns:
- Pose3d object representing the robot's position and orientation relative to the target
-
getCameraPose3d_TargetSpace
Gets the camera's 3D pose with respect to the currently tracked target's coordinate system.- Parameters:
limelightName
- Name/identifier of the Limelight- Returns:
- Pose3d object representing the camera's position and orientation relative to the target
-
getTargetPose3d_CameraSpace
Gets the target's 3D pose with respect to the camera's coordinate system.- Parameters:
limelightName
- Name/identifier of the Limelight- Returns:
- Pose3d object representing the target's position and orientation relative to the camera
-
getTargetPose3d_RobotSpace
Gets the target's 3D pose with respect to the robot's coordinate system.- Parameters:
limelightName
- Name/identifier of the Limelight- Returns:
- Pose3d object representing the target's position and orientation relative to the robot
-
getCameraPose3d_RobotSpace
Gets the camera's 3D pose with respect to the robot's coordinate system.- Parameters:
limelightName
- Name/identifier of the Limelight- Returns:
- Pose3d object representing the camera's position and orientation relative to the robot
-
getBotPose2d_wpiBlue
Gets the Pose2d for easy use with Odometry vision pose estimator (addVisionMeasurement)- Parameters:
limelightName
-- Returns:
-
getBotPoseEstimate_wpiBlue
Gets the MegaTag1 Pose2d and timestamp for use with WPILib pose estimator (addVisionMeasurement) in the WPILib Blue alliance coordinate system.- Parameters:
limelightName
-- Returns:
-
getBotPoseEstimate_wpiBlue_MegaTag2
public static LimelightHelpers.PoseEstimate getBotPoseEstimate_wpiBlue_MegaTag2(String limelightName) Gets the MegaTag2 Pose2d and timestamp for use with WPILib pose estimator (addVisionMeasurement) in the WPILib Blue alliance coordinate system. Make sure you are calling setRobotOrientation() before calling this method.- Parameters:
limelightName
-- Returns:
-
getBotPose2d_wpiRed
Gets the Pose2d for easy use with Odometry vision pose estimator (addVisionMeasurement)- Parameters:
limelightName
-- Returns:
-
getBotPoseEstimate_wpiRed
Gets the Pose2d and timestamp for use with WPILib pose estimator (addVisionMeasurement) when you are on the RED alliance- Parameters:
limelightName
-- Returns:
-
getBotPoseEstimate_wpiRed_MegaTag2
public static LimelightHelpers.PoseEstimate getBotPoseEstimate_wpiRed_MegaTag2(String limelightName) Gets the Pose2d and timestamp for use with WPILib pose estimator (addVisionMeasurement) when you are on the RED alliance- Parameters:
limelightName
-- Returns:
-
getBotPose2d
Gets the Pose2d for easy use with Odometry vision pose estimator (addVisionMeasurement)- Parameters:
limelightName
-- Returns:
-
getIMUData
Gets the current IMU data from NetworkTables. IMU data is formatted as [robotYaw, Roll, Pitch, Yaw, gyroX, gyroY, gyroZ, accelX, accelY, accelZ]. Returns all zeros if data is invalid or unavailable.- Parameters:
limelightName
- Name/identifier of the Limelight- Returns:
- IMUData object containing all current IMU data
-
setPipelineIndex
-
setPriorityTagID
-
setLEDMode_PipelineControl
Sets LED mode to be controlled by the current pipeline.- Parameters:
limelightName
- Name of the Limelight camera
-
setLEDMode_ForceOff
-
setLEDMode_ForceBlink
-
setLEDMode_ForceOn
-
setStreamMode_Standard
Enables standard side-by-side stream mode.- Parameters:
limelightName
- Name of the Limelight camera
-
setStreamMode_PiPMain
Enables Picture-in-Picture mode with secondary stream in the corner.- Parameters:
limelightName
- Name of the Limelight camera
-
setStreamMode_PiPSecondary
Enables Picture-in-Picture mode with primary stream in the corner.- Parameters:
limelightName
- Name of the Limelight camera
-
setCropWindow
public static void setCropWindow(String limelightName, double cropXMin, double cropXMax, double cropYMin, double cropYMax) Sets the crop window for the camera. The crop window in the UI must be completely open.- Parameters:
limelightName
- Name of the Limelight cameracropXMin
- Minimum X value (-1 to 1)cropXMax
- Maximum X value (-1 to 1)cropYMin
- Minimum Y value (-1 to 1)cropYMax
- Maximum Y value (-1 to 1)
-
setFiducial3DOffset
public static void setFiducial3DOffset(String limelightName, double offsetX, double offsetY, double offsetZ) Sets 3D offset point for easy 3D targeting. -
SetRobotOrientation
public static void SetRobotOrientation(String limelightName, double yaw, double yawRate, double pitch, double pitchRate, double roll, double rollRate) Sets robot orientation values used by MegaTag2 localization algorithm.- Parameters:
limelightName
- Name/identifier of the Limelightyaw
- Robot yaw in degrees. 0 = robot facing red alliance wall in FRCyawRate
- (Unnecessary) Angular velocity of robot yaw in degrees per secondpitch
- (Unnecessary) Robot pitch in degreespitchRate
- (Unnecessary) Angular velocity of robot pitch in degrees per secondroll
- (Unnecessary) Robot roll in degreesrollRate
- (Unnecessary) Angular velocity of robot roll in degrees per second
-
SetRobotOrientation_NoFlush
public static void SetRobotOrientation_NoFlush(String limelightName, double yaw, double yawRate, double pitch, double pitchRate, double roll, double rollRate) -
SetIMUMode
Configures the IMU mode for MegaTag2 Localization- Parameters:
limelightName
- Name/identifier of the Limelightmode
- IMU mode.
-
SetFidcuial3DOffset
Sets the 3D point-of-interest offset for the current fiducial pipeline. https://docs.limelightvision.io/docs/docs-limelight/pipeline-apriltag/apriltag-3d#point-of-interest-tracking- Parameters:
limelightName
- Name/identifier of the Limelightx
- X offset in metersy
- Y offset in metersz
- Z offset in meters
-
SetFiducialIDFiltersOverride
Overrides the valid AprilTag IDs that will be used for localization. Tags not in this list will be ignored for robot pose estimation.- Parameters:
limelightName
- Name/identifier of the LimelightvalidIDs
- Array of valid AprilTag IDs to track
-
SetFiducialDownscalingOverride
Sets the downscaling factor for AprilTag detection. Increasing downscale can improve performance at the cost of potentially reduced detection range.- Parameters:
limelightName
- Name/identifier of the Limelightdownscale
- Downscale factor. Valid values: 1.0 (no downscale), 1.5, 2.0, 3.0, 4.0. Set to 0 for pipeline control.
-
setCameraPose_RobotSpace
public static void setCameraPose_RobotSpace(String limelightName, double forward, double side, double up, double roll, double pitch, double yaw) Sets the camera pose relative to the robot.- Parameters:
limelightName
- Name of the Limelight cameraforward
- Forward offset in metersside
- Side offset in metersup
- Up offset in metersroll
- Roll angle in degreespitch
- Pitch angle in degreesyaw
- Yaw angle in degrees
-
setPythonScriptData
-
getPythonScriptData
-
takeSnapshot
Asynchronously take snapshot. -
getLatestResults
Gets the latest JSON results output and returns a LimelightResults object.- Parameters:
limelightName
- Name of the Limelight camera- Returns:
- LimelightResults object containing all current target data
-