Skip to main content
LimelightResults is the deserialized form of the Limelight’s full JSON output. It is returned by LimelightHelpers.getLatestResults(limelightName), which fetches the json NetworkTables entry and parses it with Jackson.
LimelightResults results = LimelightHelpers.getLatestResults("limelight");
For high-frequency robot loops, prefer the direct NetworkTables methods — getRawFiducials, getBotPoseEstimate_wpiBlue, getTX, etc. — over getLatestResults(). JSON parsing adds measurable latency (latency_jsonParse records the cost per call) and allocates garbage on every invocation. Reserve getLatestResults() for tasks where you need the full result set: iterating all detector outputs, reading barcode data, or logging diagnostics.

Top-level fields

error
String
Non-empty if JSON parsing failed or the NT entry was empty. Always check this field before using any other data. Example values: "lljson error: empty json", "lljson error: <Jackson message>".
pipelineID
double
Active pipeline index at the time the frame was processed. Maps to JSON key pID.
latency_pipeline
double
Pipeline processing latency in milliseconds. Maps to JSON key tl.
latency_capture
double
Image capture latency in milliseconds. Maps to JSON key cl.
latency_jsonParse
double
Time to parse the JSON string in the library, in milliseconds. Set by getLatestResults() after deserialization — not part of the Limelight JSON payload.
timestamp_LIMELIGHT_publish
double
Limelight-side publish timestamp. Maps to JSON key ts.
timestamp_RIOFPGA_capture
double
RoboRIO FPGA timestamp at the moment NetworkTables captured the entry. Maps to JSON key ts_rio.
timestamp_nt
long
NetworkTables timestamp in microseconds. Maps to JSON key ts_nt.
timestamp_sys
long
System timestamp. Maps to JSON key ts_sys.
timestamp_us
long
Microsecond timestamp. Maps to JSON key ts_us.
valid
boolean
Whether the pipeline produced valid results for this frame. Maps to JSON key v (encoded as a number: 0 or 1).
pipelineType
String
Active pipeline type string, e.g. "retro", "apriltag", "neural_detector". Maps to JSON key pTYPE.

Primary target values

tx
double
Horizontal offset from the crosshair to the primary target in degrees.
ty
double
Vertical offset from the crosshair to the primary target in degrees.
tx_nocrosshair
double
Horizontal offset from the camera’s principal point (no crosshair correction) in degrees. Maps to JSON key txnc.
ty_nocrosshair
double
Vertical offset from the camera’s principal point in degrees. Maps to JSON key tync.
ta
double
Primary target area as a percentage of the image (0–100).

Robot pose arrays

Each pose array has 6 elements: [x, y, z, roll, pitch, yaw]. Translation is in meters; angles are in degrees. Use the WPILib Blue variants for new code.
botpose
double[6]
Robot pose in the field-origin coordinate system.
botpose_wpiblue
double[6]
Robot pose in the WPILib Blue alliance coordinate system (origin at the blue alliance wall). Preferred for pose estimator integration.
botpose_wpired
double[6]
Robot pose in the WPILib Red alliance coordinate system.
botpose_tagcount
double
Number of AprilTags used to compute the MegaTag1 pose.
botpose_span
double
Distance in meters between the two outermost contributing tags.
botpose_avgdist
double
Average distance in meters from the camera to contributing tags.
botpose_avgarea
double
Average tag area (% of image) across all contributing tags.

MegaTag2 pose arrays

botpose_orb
double[6]
MegaTag2 robot pose in the field-origin coordinate system.
botpose_orb_wpiblue
double[6]
MegaTag2 robot pose in the WPILib Blue alliance coordinate system.
botpose_orb_wpired
double[6]
MegaTag2 robot pose in the WPILib Red alliance coordinate system.

Pose helper methods

LimelightResults exposes convenience methods to convert the raw arrays to WPILib geometry objects:
MethodReturnsSource array
getBotPose2d()Pose2dbotpose
getBotPose2d_wpiBlue()Pose2dbotpose_wpiblue
getBotPose2d_wpiRed()Pose2dbotpose_wpired
getBotPose3d()Pose3dbotpose
getBotPose3d_wpiBlue()Pose3dbotpose_wpiblue
getBotPose3d_wpiRed()Pose3dbotpose_wpired

Target arrays

targets_Retro
LimelightTarget_Retro[]
Color/retroreflective pipeline targets. Each entry includes ta, tx, ty, tx_pixels, ty_pixels, tx_nocrosshair, ty_nocrosshair, and pose methods (getCameraPose_TargetSpace, getRobotPose_FieldSpace, etc.).
targets_Fiducials
LimelightTarget_Fiducial[]
AprilTag pipeline targets. See LimelightTarget_Fiducial below.
targets_Classifier
LimelightTarget_Classifier[]
Neural classifier pipeline results. Each entry includes className (String), classID (double), confidence (double), zone (double), tx, ty, tx_pixels, ty_pixels.
targets_Detector
LimelightTarget_Detector[]
Neural detector pipeline results. Each entry includes className (String), classID (double), confidence (double), ta, tx, ty, tx_pixels, ty_pixels, tx_nocrosshair, ty_nocrosshair.
targets_Barcode
LimelightTarget_Barcode[]
Barcode pipeline results. See LimelightTarget_Barcode below.

Hardware and diagnostic fields

hardware
HardwareReport
Limelight hardware statistics for the current frame.
imuResults
IMUResults
IMU data from the JSON payload. After parsing, getLatestResults() calls imuResults.parseDataArray() internally, which populates robotYaw, roll, pitch, rawYaw, gyroX/Y/Z, and accelX/Y/Z from the raw data array. For direct NT access without JSON, see getIMUData.
rewindStats
RewindStats
Capture rewind buffer statistics for the current frame.
pythonOutput
double[]
Output values written by a Python snap script running on the Limelight. Maps to JSON key PythonOut.

LimelightTarget_Fiducial fields

fiducialID
double
AprilTag ID. Maps to JSON key fID.
fiducialFamily
String
Tag family string, e.g. "tag36h11". Maps to JSON key fam.
ta
double
Tag area as a percentage of the image.
tx
double
Horizontal offset from the crosshair to the tag center in degrees.
ty
double
Vertical offset from the crosshair to the tag center in degrees.
tx_pixels
double
Horizontal position of the tag center in pixels. Maps to JSON key txp.
ty_pixels
double
Vertical position of the tag center in pixels. Maps to JSON key typ.
tx_nocrosshair
double
Horizontal offset from the camera’s principal point in degrees. Maps to JSON key tx_nocross.
ty_nocrosshair
double
Vertical offset from the camera’s principal point in degrees. Maps to JSON key ty_nocross.
LimelightTarget_Fiducial also exposes the same set of pose methods as LimelightTarget_Retro: getCameraPose_TargetSpace(), getRobotPose_FieldSpace(), getRobotPose_TargetSpace(), getTargetPose_CameraSpace(), getTargetPose_RobotSpace(), and their 2D counterparts. All return Pose3d / Pose2d respectively.

LimelightTarget_Barcode fields

family
String
Barcode symbology, e.g. "QR", "DataMatrix", "Code128". Maps to JSON key fam.
data
String
Decoded text content of the barcode. Maps to JSON key data.
tx
double
Horizontal offset from the crosshair to the barcode center in degrees.
ty
double
Vertical offset from the crosshair to the barcode center in degrees.
tx_pixels
double
Horizontal pixel position of the barcode center. Maps to JSON key txp.
ty_pixels
double
Vertical pixel position of the barcode center. Maps to JSON key typ.
ta
double
Barcode area as a percentage of the image.
corners
double[][]
Corner point coordinates of the barcode bounding polygon. Maps to JSON key pts. Each element is a 2-element array [x, y] in pixel coordinates.

Code example

LimelightResults results = LimelightHelpers.getLatestResults("limelight");

// Guard against parse failures.
if (results.error != null && !results.error.isEmpty()) {
    DriverStation.reportWarning("Limelight JSON error: " + results.error, false);
    return;
}

if (!results.valid) {
    return;
}

// Iterate over all detected fiducial targets.
for (LimelightHelpers.LimelightTarget_Fiducial tag : results.targets_Fiducials) {
    int id = (int) tag.fiducialID;
    double dist = tag.getCameraPose_TargetSpace().getTranslation().getNorm();
    System.out.printf("Tag %d  tx=%.1f°  dist=%.2f m%n", id, tag.tx, dist);
}

// Read barcode data.
for (LimelightHelpers.LimelightTarget_Barcode barcode : results.targets_Barcode) {
    System.out.printf("Barcode [%s]: %s%n", barcode.family, barcode.data);
}

// Check hardware temperature.
if (results.hardware != null && results.hardware.temperature > 70.0) {
    DriverStation.reportWarning("Limelight temperature high: "
        + results.hardware.temperature + "°C", false);
}

// Log JSON parse cost.
SmartDashboard.putNumber("LL/jsonParseMs", results.latency_jsonParse);

Build docs developers (and LLMs) love