Limelight (Alternative Pipeline)
Limelight is an all-in-one vision camera that combines hardware, coprocessor, and software in a single unit. It takes a fundamentally different approach from PhotonVision: rather than configuring open-source software on general hardware, you configure a purpose-built device through a web dashboard and read results from a well-defined NetworkTables API.
By the end of this lesson, you will:
- Explain the architectural difference between Limelight and the PhotonVision + coprocessor approach
- Connect to the Limelight web dashboard and configure an AprilTag pipeline
- Read target data from Limelight's NetworkTables API using both raw NT keys and
LimelightHelpers - Use
LimelightHelpers.getBotPoseEstimate_wpiBlue()to get a robot pose estimate equivalent to PhotonPoseEstimator - Set the robot orientation for MegaTag 2 using
SetRobotOrientation()before each pose read - Choose between PhotonVision and Limelight based on your team's needs and constraints
What Limelight Is
Limelight is a commercial vision system produced by Limelight Robotics. Unlike PhotonVision — which is open-source software you install on a Raspberry Pi or similar coprocessor that you purchase separately — Limelight ships as a complete unit: a small camera module with an integrated processor running proprietary firmware. You mount it on the robot, connect it to the network switch, power it with a USB-C cable, and it's ready to configure.
The tradeoffs are real and worth understanding. Limelight's integration is tighter — fewer moving parts, one device to configure, one IP address to remember, no SD card to flash. The firmware is maintained by a professional team with FRC-specific focus. The web dashboard is polished and updates are delivered as OTA firmware updates. On the other hand, you're dependent on a commercial vendor for updates and bug fixes, the hardware isn't repairable if it breaks, and some advanced configurations require a paid license tier.
Both approaches work. Teams at championship level use both. The decision depends on your team's situation, covered at the end of this lesson.
As of 2025, Limelight offers the Limelight 2+ (older, widely available) and Limelight 3/3G (newer, faster processing, better detection range). The 3G model includes an integrated neural network accelerator for game piece detection (Lesson 10). Some advanced features — including certain MegaTag configurations and neural network models — require a paid Limelight "Plus" license. The base AprilTag detection and MegaTag pose estimation covered in this lesson are available without a license on current hardware. Verify the current licensing terms at docs.limelightvision.io before competition-day setup.
Limelight-Specific Concepts
Limelight's equivalent of PhotonVision's MULTI_TAG_PNP_ON_COPROCESSOR. Combines all visible AprilTag detections into a single robot pose estimate. MegaTag 1 uses tag data alone; MegaTag 2 also fuses the robot's current gyro heading (provided by your code) to improve accuracy.
Limelight computes the robot's field pose internally and publishes it as a NetworkTables array. The WPILib-compatible variant is botpose_wpiblue — the pose expressed in blue-alliance coordinates matching the WPILib field frame (Lesson 2). Always use this variant, not the raw botpose key.
MegaTag 2 requires your robot's current yaw (and optionally yaw rate, pitch, pitch rate, roll, roll rate) to constrain the pose solution. You must call LimelightHelpers.SetRobotOrientation() every loop before reading a MegaTag 2 estimate, or it will use stale orientation data.
Limelight provides a LimelightHelpers.java utility class (downloaded from docs.limelightvision.io and dropped into your project) that wraps the raw NetworkTables calls into convenient static methods. It also provides PoseEstimate objects with timestamps for direct use with addVisionMeasurement().
How Data Flows: PhotonVision vs. Limelight
Select each system to see how detection data travels from camera to robot code. The key difference is whether pose estimation happens on the coprocessor (PhotonVision) or inside the Limelight hardware (Limelight).
/photonvision/{cameraName}/rawBytes. PhotonLib on the roboRIO deserializes these and PhotonPoseEstimator chains the transforms into a robot pose. The roboRIO performs the transform chain computation.
Setting Up Limelight
Physical Connection
Connect the Limelight to the robot's network switch with an Ethernet cable. Power it from a USB-C port on the robot (typically from the VRM or PDH's USB port — check the Limelight's current draw spec against your available current). The Limelight is accessible at http://limelight.local:5801 or its static IP once connected to the robot network.
Assign a static IP in the 10.TE.AM.11 range (your team number). This is critical for competition — DHCP is unreliable in the match queue. Set the static IP in the Limelight dashboard Settings tab and document it.
Pipeline Configuration
Open the Limelight dashboard and create an "AprilTag" pipeline. The key settings:
- Tag Family: Set to "Tag 36h11" to match the FRC field standard.
- Max Corner Ambiguity: This is Limelight's name for the pose ambiguity threshold. Leave at default (0.35) initially; lower values reject more ambiguous estimates. Covered further in Lesson 8.
- Robot Offset: The 3D offset from the Limelight camera to the robot's center. This is the robot-to-camera transform concept from Lesson 2, entered directly in the Limelight UI instead of in code. Limelight uses this to compute
botposeautomatically. - Field Map: Select the correct season's field layout. Limelight maintains its own copy of the official FIRST tag layout — select the matching year.
Unlike PhotonVision where the robot-to-camera transform is configured in VisionConstants.java and passed to PhotonPoseEstimator, Limelight takes the camera offset directly in its web dashboard under the "Robot Offset" fields. This is convenient — one place to update it — but it means the offset isn't in version control with your code. When the camera mount changes, you must update both the robot's physical configuration and remember to update the Limelight dashboard. Put a comment in your VisionConstants.java referencing the Limelight's offset values so the numbers are documented in one place even though they're configured elsewhere.
Adding LimelightHelpers to Your Project
Download LimelightHelpers.java from docs.limelightvision.io/en/latest/docs/apis/limelight-lib.html. Drop the file directly into your src/main/java/frc/robot/ directory (or a util/ subdirectory). No vendor dep file is needed — it's a single self-contained Java class that reads from NetworkTables directly. Add import frc.robot.LimelightHelpers; or adjust the import path based on where you placed the file.
Limelight updates LimelightHelpers.java every season to add new API methods, fix bugs, and support new firmware features. If you copy last year's file into this year's project, you may be missing new methods (like getBotPoseEstimate_wpiBlue_MegaTag2() introduced in later firmware) or using deprecated ones. Always download a fresh copy from the docs at the start of each season and verify the file's header comment shows the current year's version number.
Reading Pose Estimates with LimelightHelpers
The primary use case in competition is getting a robot pose estimate — the equivalent of PhotonPoseEstimator.update(). Limelight provides two MegaTag variants; MegaTag 2 is preferred because it uses the robot's gyro heading to constrain the pose solution, reducing heading ambiguity.
import frc.robot.LimelightHelpers; import frc.robot.LimelightHelpers.PoseEstimate; public class VisionSubsystem extends SubsystemBase { // Limelight name must match what's configured in the dashboard. // Default name is "limelight". If you renamed it, use that name here. private static final String LL_NAME = "limelight"; private final DriveSubsystem m_drive; public VisionSubsystem(DriveSubsystem drive) { m_drive = drive; } @Override public void periodic() { // ── CRITICAL: Set robot orientation BEFORE reading MegaTag 2 ────────── // MegaTag 2 uses the gyro heading to disambiguate pose solutions. // You MUST update this every loop or the Limelight uses stale orientation. // Parameters: name, yawDegrees, yawRateDPS, pitchDegrees, pitchRateDPS, // rollDegrees, rollRateDPS LimelightHelpers.SetRobotOrientation( LL_NAME, m_drive.getHeadingDegrees(), // current yaw from Pigeon 2 / NavX 0, // yaw rate (0 = don't use) 0, 0, 0, 0); // pitch/roll (typically 0 for ground robot) // ── Get MegaTag 2 pose estimate ─────────────────────────────────────── // Returns a PoseEstimate object — check tagCount > 0 before using PoseEstimate estimate = LimelightHelpers.getBotPoseEstimate_wpiBlue_MegaTag2(LL_NAME); if (estimate != null && estimate.tagCount > 0) { // Additional quality filter: reject if avg tag distance is too large // (far tags have high pixel noise → poor pose accuracy) if (estimate.avgTagDist < 5.0) { // meters // estimate.pose — Pose2d in WPILib blue-origin field frame // estimate.timestampSeconds — capture time (not current time) // estimate.tagCount — number of tags used // estimate.avgTagDist — average distance to detected tags m_drive.addVisionMeasurement( estimate.pose, estimate.timestampSeconds); SmartDashboard.putNumber("LL/TagCount", estimate.tagCount); SmartDashboard.putNumber("LL/AvgTagDist", estimate.avgTagDist); } } } }
Raw NetworkTables API (without LimelightHelpers)
If you prefer to avoid the helper class or need custom processing, Limelight's data is available directly on NetworkTables. This is also useful for understanding what LimelightHelpers does internally.
import edu.wpi.first.networktables.NetworkTableInstance; import edu.wpi.first.networktables.NetworkTable; // Get the Limelight's NetworkTable by name NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight"); // Target present (1 = has targets, 0 = no targets) long tv = limelightTable.getEntry("tv").getInteger(0); boolean hasTargets = tv == 1L; // Tag ID of the primary target long tid = limelightTable.getEntry("tid").getInteger(-1); // Horizontal angle to target (degrees) — negative = left, positive = right double tx = limelightTable.getEntry("tx").getDouble(0.0); // Vertical angle to target (degrees) double ty = limelightTable.getEntry("ty").getDouble(0.0); // BotPose in WPILib blue-origin coordinates // Array: [x, y, z, roll, pitch, yaw, latency_ms, tagCount, tagSpan, avgTagDist, avgTagArea] double[] botPoseWpiBlue = limelightTable.getEntry("botpose_wpiblue") .getDoubleArray(new double[11]); double poseX = botPoseWpiBlue[0]; // field X (meters) double poseY = botPoseWpiBlue[1]; // field Y (meters) double yawDeg = botPoseWpiBlue[5]; // heading (degrees) double latency = botPoseWpiBlue[6]; // pipeline latency (ms) double tagCount = botPoseWpiBlue[7]; // number of tags used // Compute capture timestamp for addVisionMeasurement(): // FPGA time minus total latency (pipeline + network) double timestamp = Timer.getFPGATimestamp() - (latency / 1000.0) // pipeline latency in seconds - 0.011; // approximate NetworkTables transmission overhead // LimelightHelpers does this calculation internally — prefer it over manual NT access
Limelight publishes several botpose variants: botpose (Limelight's own coordinate frame — origin at field center), botpose_wpiblue (WPILib blue-origin frame), and botpose_wpired (WPILib red-origin frame). Only botpose_wpiblue matches the coordinate system used by SwerveDrivePoseEstimator and PathPlanner. Using botpose (field-center origin) produces poses that appear to track correctly but are offset by half the field length and width from where the robot actually is — exactly the kind of systematic wrong-looking-right error that causes teams to chase a ghost during autonomous. Always use _wpiblue. Always.
MegaTag 1 vs. MegaTag 2
Limelight offers two MegaTag variants. The choice affects accuracy, especially for heading estimation.
| Aspect | MegaTag 1 | MegaTag 2 (preferred) |
|---|---|---|
| Robot orientation input | Not used | Requires current gyro yaw via SetRobotOrientation() before each read |
| Heading accuracy | Computed from tags only — heading ambiguity problem at some distances | Gyro constrains the heading solution — much more accurate, no ambiguity |
| Position accuracy | Good with multiple tags | Better — gyro heading reduces the degrees of freedom in the optimization |
| Failure mode | Can produce flipped heading estimates at certain distances | If SetRobotOrientation() is stale or wrong, the heading constraint corrupts the estimate |
| Method | getBotPoseEstimate_wpiBlue() |
getBotPoseEstimate_wpiBlue_MegaTag2() |
MegaTag 2's heading improvement is only as good as the gyro heading you provide. If your Pigeon 2 or NavX hasn't been zeroed correctly, or if the robot was bumped and the gyro has accumulated drift, the orientation you provide to SetRobotOrientation() is wrong — and MegaTag 2's "improvement" becomes a source of systematic error. For robust competition performance: always reset the gyro as part of autonomousInit(), and consider rejecting MegaTag 2 estimates when your gyro confidence is low (after a hard collision, for example). The same gyro that powers your swerve drive's field-oriented control is the one MegaTag 2 depends on — they succeed and fail together.
PhotonVision vs. Limelight: Choosing Your System
| Aspect | PhotonVision | Limelight |
|---|---|---|
| Hardware | Separate coprocessor (Raspberry Pi, Orange Pi) + USB camera. Flexible, repairable, reusable across seasons. | All-in-one device. Compact, consistent. One SKU to buy, one thing to mount. |
| Software | Open-source. Community-maintained. Full source available. Runs on your hardware. | Proprietary firmware. Maintained by Limelight Robotics. OTA updates. |
| Cost | ~$50–$80 for Pi 4 + camera. Very low total cost. | $100–$400 depending on model. Higher hardware cost but simpler setup. |
| Setup time | Flash SD card, configure dashboard, write calibration. ~2–4 hours for first camera. | Power on, configure dashboard, done. ~30 minutes for first camera. |
| Java API | PhotonLib via vendor dep. PhotonPoseEstimator handles all transform chain logic. |
LimelightHelpers.java dropped into project. getBotPoseEstimate_wpiBlue_MegaTag2(). |
| Calibration | Required. Manual process (25–50 images). Quality depends on user effort. | Factory-calibrated. No user calibration needed for basic AprilTag detection. |
| Multi-camera | Any number of cameras on the same or different coprocessors. | One Limelight per camera port. Multiple units for multiple cameras. |
| Game piece detection | Separate neural net pipeline (Lesson 10). Custom model training possible. | Limelight 3G has integrated neural net. Pre-trained game piece models available. |
- Budget is a constraint — coprocessor + camera is significantly cheaper
- You want full control and visibility into the processing pipeline
- You need custom neural net models for non-standard game pieces
- Your team values open-source tooling and community support
- You already have Raspberry Pi hardware from previous seasons
- You need deep integration with AdvantageKit logging
- Setup time is at a premium — one device, minimal configuration
- Your team lacks a programmer comfortable with coprocessor setup
- You want factory-calibrated hardware and OTA updates
- You're using the Limelight 3G for both AprilTags and game piece detection
- Reliability and consistency across events matters more than customizability
- Budget allows the higher hardware cost
Team 2910 (Jack in the Bot) uses PhotonVision on dedicated coprocessors for AprilTag pose estimation. The reasons are consistent with the PhotonVision column above: tight integration with AdvantageKit logging for replay debugging, familiarity with the open-source toolchain, and the ability to customize the processing pipeline for specific game requirements. That said, both approaches produce competitive results when configured correctly. Teams at championship level have won with both. The tool matters less than the implementation quality.
🔌 System Check
Work through this list before any match that uses Limelight pose estimation:
- Limelight dashboard is accessible at its static IP. Navigate to
http://10.TE.AM.11:5801(your static IP) and confirm the dashboard loads. Verify the live stream shows the camera view and tags are outlined in green when visible. - Field map is set to the current season. In the pipeline settings, confirm the field map dropdown shows the current year's game. Using last year's field map produces wrong
botposevalues because tag positions have changed. - Camera offset is configured correctly. In the Limelight dashboard, verify the "Robot Offset" fields show the correct camera position on your robot (forward/right/up offsets in meters, yaw/pitch/roll in degrees). If these are from a previous robot configuration, update them.
SetRobotOrientation()is called in periodic() before reading MegaTag 2. Add a SmartDashboard boolean that is true whenSetRobotOrientation()was called this loop. Confirm it's always true during autonomous — if it becomes false, the heading constraint is stale.botpose_wpibluecoordinates match expected field positions. With the robot at a known field position facing a tag, verify the logged X and Y fromgetBotPoseEstimate_wpiBlue_MegaTag2()match the robot's physical position to within 10 cm. If the values are off by ~8 m in X or ~4 m in Y, you're readingbotpose(field-center origin) instead ofbotpose_wpiblue.
Knowledge Check
1. A team reads the Limelight's pose using LimelightHelpers.getBotPoseEstimate_wpiBlue_MegaTag2() but forgets to call SetRobotOrientation() in periodic(). The robot has been running for 30 seconds. What is the most likely consequence?
2. A team's robot is on the red alliance side (X ≈ 15 m) and the Limelight is reading tags. SmartDashboard shows LL/PoseX ≈ 6.77 m — roughly half the expected value. What is the most likely cause?
3. A team wants to use a Limelight for AprilTag pose estimation AND a custom neural network model for detecting off-the-shelf orange balls that are not standard FRC game pieces. Which Limelight capability limitation should they be aware of?
Configure and Test Limelight Pose Estimation
- If you have access to a Limelight: power it on and connect it to your robot network. Set a static IP. Confirm the dashboard loads. Create an AprilTag pipeline, set the tag family to Tag 36h11, and set the current season's field map. Point the Limelight at a tag and confirm green outlines appear in the stream.
- Download
LimelightHelpers.javafromdocs.limelightvision.ioand add it to your project. Write a minimalVisionSubsystemthat callsSetRobotOrientation()with your drivetrain's heading, then reads a MegaTag 2 estimate and logstagCount,avgTagDist, and the pose X/Y to SmartDashboard. Confirm the values update live. - Add the camera offset to the Limelight dashboard (forward/right/up from robot center in meters). Verify by checking whether the pose output matches your robot's known physical position on the field. Document the offset values in a comment in
VisionConstants.javaeven though they're configured in the dashboard — version control needs to know these numbers. - Intentionally break the orientation update: comment out the
SetRobotOrientation()call and drive the robot in a 180° arc. Observe how the MegaTag 2 pose estimate degrades as the heading gets staler. Restore the call and confirm estimates are stable again. This exercise demonstrates exactly why the call must happen every loop. - Bonus: If your team currently uses PhotonVision: write a
VisionSubsystemthat accepts both aPhotonPoseEstimatorand a Limelight MegaTag 2 estimate, and passes both toaddVisionMeasurement(). This dual-system approach gives you both the flexibility of PhotonVision and the simplicity of Limelight's factory calibration. Compare the two estimates — are they consistent? What happens when they disagree?