Unit 10 · Lesson 3

Introduction to PhotonVision

PhotonVision is the software layer between a USB camera and your robot code. It runs on a coprocessor, handles all the image processing, and delivers clean detection results over NetworkTables. This lesson covers installation, AprilTag pipeline configuration, camera calibration, and reading detections from Java.

By the end of this lesson, you will:

  • Install PhotonVision on a coprocessor and access the web dashboard
  • Create an AprilTag pipeline and configure the critical settings: tag family, resolution, and exposure
  • Explain why camera calibration is required for pose estimation and perform a basic calibration using a chessboard pattern
  • Add PhotonLib to a robot project and instantiate a PhotonCamera with the correct camera name
  • Read detection results using getLatestResult(), iterate targets, and access tag ID, transform, and ambiguity
  • Identify the three most common PhotonVision configuration mistakes and their symptoms

What PhotonVision Is

PhotonVision is an open-source vision processing platform built specifically for FRC. It runs as a service on a dedicated coprocessor — typically a Raspberry Pi 4, Orange Pi 5, or similar single-board computer — separate from the roboRIO. The coprocessor connects to one or more USB cameras, runs the image processing pipeline, and publishes detection results to NetworkTables on the robot's network.

The separation from the roboRIO is intentional and important. AprilTag detection is computationally expensive. Running it on the roboRIO would consume CPU time needed for the 20 ms control loop. By offloading detection to a dedicated coprocessor, the roboRIO only receives the finished results: tag IDs, transforms, and ambiguity scores. The roboRIO's loop time remains unaffected.

PhotonVision exposes a browser-based web dashboard for configuration — you connect to it from your laptop over the robot network. No SSH, no command line required for basic setup. Once configured, the settings persist through power cycles. The Java library (PhotonLib) provides the API your robot code uses to read results.

💡 PhotonVision vs. running detection on the roboRIO

WPILib includes an AprilTagDetector class that can run detection directly on the roboRIO without any coprocessor. This is useful for quick testing or for robots without coprocessor budget, but it comes with significant constraints: lower frame rates (often 5–15 fps vs. 30–90 fps on a coprocessor), higher loop time impact, and reduced detection range due to resolution limits. For competition, a dedicated coprocessor running PhotonVision is strongly preferred. The performance difference is not marginal — it's the difference between detecting tags at 2 meters and detecting them at 6+ meters.

Installation

Installing PhotonVision on the Coprocessor

Download the latest PhotonVision release from github.com/PhotonVision/photonvision/releases. Choose the image file for your specific coprocessor hardware (Raspberry Pi 4, Orange Pi 5, etc.). Flash the image to a microSD card using Balena Etcher or a similar tool. Insert the card into the coprocessor, connect it to the robot's network switch, and power it on.

After approximately 30–60 seconds of boot time, PhotonVision is accessible at http://photonvision.local:5800 from any laptop on the robot network. If mDNS resolution isn't working, try the IP address directly — check your router's DHCP table or use a network scanner to find the coprocessor's IP.

🔍 Static IP vs. DHCP for the coprocessor

PhotonVision's web UI lets you assign a static IP to the coprocessor from the Settings tab. For competition, always assign a static IP in the 10.TE.AM.11 range (where TE.AM is your four-digit team number). DHCP works in the shop but is unreliable at competition venues where multiple robots share a network switch — the coprocessor may get a different IP between matches, making it impossible to access the dashboard in the queue. Set the static IP during pre-season setup and document it in your team's pit guide.

Adding PhotonLib to Your Robot Project

Installing PhotonLib — vendor dependency
// In VS Code: W key → "Manage Vendor Libraries" → "Install new libraries (online)"
// Paste this URL for the current release:
// https://maven.photonvision.org/repository/internal/org/photonvision/
//         PhotonLib-json/1.0/PhotonLib-json-1.0.json
//
// The exact URL changes each season — always get the current one from:
// docs.photonvision.org/en/latest/docs/programming/photonlib/adding-vendordep.html
//
// After installing, verify the dependency appears in vendordeps/photonlib.json
// and that your build.gradle shows it in the dependencies block.

// Verify the install compiled cleanly by adding this import to any Java file:
import org.photonvision.PhotonCamera;
// If VS Code resolves it without errors, PhotonLib is installed correctly.
💡 PhotonLib version must match PhotonVision firmware version

The Java library version and the firmware version running on the coprocessor must match — or at minimum be compatible within the same major version. A mismatch can cause deserialization errors where the NetworkTables data format differs between versions, producing empty result sets or garbled detections with no error message. After flashing new PhotonVision firmware, always update the PhotonLib vendordep to the matching version. The PhotonVision web UI shows the running firmware version in the top-right corner.

Configuring an AprilTag Pipeline

A PhotonVision pipeline is a named configuration that tells the coprocessor how to process images from one camera. Each camera can have multiple pipelines (e.g., one for AprilTags, one for game pieces), and you switch between them from your robot code or the dashboard. Walk through the configuration steps below — each one is a required setting for reliable AprilTag detection.

PhotonVision pipeline configuration — AprilTag mode step 1 of 6
1 / 6

Critical Camera Settings for AprilTag Detection

These four settings have the largest impact on detection quality. PhotonVision exposes them in the camera settings panel (the gear icon next to each camera in the dashboard). These are hardware-level settings that apply to all pipelines on that camera.

Exposure How long the shutter stays open

Lower exposure = less motion blur but requires more light. For AprilTag detection, 2–6 ms is typically correct. At 3 m/s robot velocity, a 10 ms exposure blurs the tag by ~3 cm — enough to smear corner positions and degrade pose accuracy.

Start at 3 ms, increase if too dark
Gain / Brightness Digital amplification of sensor signal

Higher gain brightens the image without changing exposure, but amplifies sensor noise. For AprilTags, noise in the binary threshold creates false edges that corrupt corner detection. Use the minimum gain that produces clear black/white tag contrast.

Keep as low as possible
Resolution Pixels per frame

Higher resolution = more tag detail at distance, but slower processing. 1280×720 is a good starting point. At 640×480 with a typical FRC camera, tags become difficult to detect reliably beyond ~4 m. Above 1920×1080, CPU load on the coprocessor increases significantly.

1280×720 @ 60fps recommended
FPS / Frame Rate Frames processed per second

Higher FPS = more frequent detection updates. At 30 fps, a new detection arrives every 33 ms. At 60 fps, every 17 ms — closer to the 20 ms robot loop. The coprocessor must be able to process frames faster than they arrive, or the pipeline backs up and latency grows.

Match to resolution capability
💡 Disable auto-exposure before competition

Many USB cameras ship with auto-exposure enabled. Auto-exposure continuously adjusts the shutter time based on overall scene brightness — which sounds helpful but is disastrous for AprilTag detection. When the robot drives from a dark corner to a bright scoring zone, the exposure changes dramatically, causing momentary motion blur and detection loss exactly when you need the tags most. Disable auto-exposure in PhotonVision's camera settings, set a fixed exposure that works under competition lighting, and never enable auto-exposure again for that camera. This is one of the most consistently impactful settings changes you can make.

Camera Calibration: Why It's Required

In Lesson 1 we learned that solvePnP converts the tag's corner pixel coordinates into a 3D pose using the camera's intrinsic calibration. The calibration tells solvePnP how the camera's lens maps 3D world points to 2D pixel coordinates — specifically: focal length (how much the lens zooms), principal point (where the optical axis intersects the sensor), and distortion coefficients (how the lens bends straight lines).

Without calibration, solvePnP uses inaccurate lens parameters. The result is systematic distance error: the algorithm thinks the camera sees the world from a slightly different geometry than it actually does. A 10% error in focal length produces roughly 10% error in distance measurements — at 4 meters, that's 40 cm of systematic bias in every pose estimate. This bias is not random; it's consistent and predictable, which makes it look like the vision system is "almost working" while being persistently wrong.

The Calibration Workflow

1
Print a calibration board

PhotonVision uses a standard chessboard or charuco board pattern. Print the board at its specified physical size — the algorithm needs to know the actual square size in millimeters. Do not scale the print to fit the page; print at 100% scale and measure the squares with a ruler to confirm. A common mistake is letting the printer "fit to page," which makes the printed squares a different size than specified and corrupts the calibration.

2
Mount the board rigidly and set camera settings first

Tape the calibration board flat to a rigid backing (MDF or foam board — not paper held by hand, which bends). Critically, calibration must be performed at the exact camera settings you'll use in competition: the same resolution, the same exposure, auto-exposure off. Calibration at 640×480 is not valid for a camera running at 1280×720. Calibrate after locking in all camera settings.

3
Capture 25–50 images from diverse angles and distances

Open the Calibration tab in PhotonVision's web UI. Move the board (or the camera, if it's easier) to fill the frame from different angles — tilted left, right, up, down, near, far, corners, center. Capture a snapshot each time. The calibration algorithm needs to see the board from many perspectives to solve for all the lens parameters accurately. Staying in one position or distance produces a calibration that only works at that distance.

4
Run calibration and verify RMS error

Click "Calibrate" in PhotonVision. The algorithm runs and reports an RMS (root mean square) reprojection error in pixels. This number measures how accurately the calibration can predict where board corners will appear in the image. A good calibration has RMS < 0.5 pixels. RMS 0.5–1.0 is acceptable. RMS > 1.0 indicates a poor calibration — usually caused by blurry images, a warped board, or insufficient angle diversity. Recalibrate rather than using a high-RMS calibration.

5
Apply and verify with a known-distance test

After calibrating, hold an AprilTag at a measured distance (e.g., exactly 2.0 m from the camera) and verify that PhotonVision's reported Z distance matches. A well-calibrated camera should read 1.95–2.05 m. If the reported distance is consistently off by more than 5%, the calibration has a systematic error — most often from printing at the wrong scale or calibrating at a different resolution. Re-check the board's printed square size and recalibrate if needed.

🔍 Recalibrate every time you change the camera setup

Calibration is specific to: the physical camera, the lens (even the same model camera can have slightly different optics), the resolution setting, and the mounting angle. If any of these change — the camera is swapped, the mount is rebuilt, or the resolution is adjusted — the calibration is no longer valid. Teams that calibrate once in pre-season and never recalibrate arrive at Week 1 events with a different robot configuration and a stale calibration producing wrong pose estimates. Build calibration into your pre-competition checklist: verify the RMS error is still below 0.5 pixels before each event.

Reading Detections with PhotonLib

Once PhotonVision is configured and the coprocessor is running, your robot code reads detection results using the PhotonLib Java library. The interface is straightforward: create a PhotonCamera with the camera's name (as set in the PhotonVision dashboard), poll getLatestResult() in periodic(), and iterate the detected targets.

VisionSubsystem.java — basic PhotonVision integration
import org.photonvision.PhotonCamera;
import org.photonvision.targeting.PhotonPipelineResult;
import org.photonvision.targeting.PhotonTrackedTarget;

public class VisionSubsystem extends SubsystemBase {

    // Camera name must EXACTLY match the name in PhotonVision's dashboard.
    // Case-sensitive. Check the camera name in the top-left dropdown of the UI.
    private final PhotonCamera m_frontCamera = new PhotonCamera("FrontCamera");

    private PhotonPipelineResult m_latestResult = new PhotonPipelineResult();

    @Override
    public void periodic() {
        // getLatestResult() returns the most recent detection frame from NetworkTables.
        // Call this once per loop and cache the result — calling it multiple times
        // in one loop can return different frames if processing is fast.
        m_latestResult = m_frontCamera.getLatestResult();

        // Log detection count for debugging
        SmartDashboard.putBoolean("Vision/HasTargets", m_latestResult.hasTargets());
        SmartDashboard.putNumber("Vision/TargetCount",
            m_latestResult.getTargets().size());
    }

    public PhotonPipelineResult getLatestResult() {
        return m_latestResult;
    }

    // Example: get the best target (highest decision margin / lowest ambiguity)
    public Optional<PhotonTrackedTarget> getBestTarget() {
        if (!m_latestResult.hasTargets()) {
            return Optional.empty();
        }
        return Optional.of(m_latestResult.getBestTarget());
    }
}
Reading target data from a PhotonTrackedTarget
// Given a PhotonTrackedTarget from getLatestResult().getTargets():
PhotonTrackedTarget target = result.getBestTarget();

// ── Identity ─────────────────────────────────────────────────────────────
int    tagId     = target.getFiducialId();
// Returns -1 if the target is not an AprilTag (e.g., a colored target)

// ── Pose confidence ──────────────────────────────────────────────────────
double ambiguity = target.getPoseAmbiguity();
// 0.0 = two solvePnP solutions equally likely (don't trust this detection)
// 1.0 = one solution strongly preferred (high confidence)
// Reject detections where ambiguity < 0.2 (covered in Lesson 8)

// ── Camera-relative geometry ──────────────────────────────────────────────
Transform3d camToTag = target.getBestCameraToTarget();
double distance = camToTag.getTranslation().getNorm();
// getNorm() = Euclidean 3D distance in meters

double yaw   = target.getYaw();    // degrees, positive = tag is to the right
double pitch = target.getPitch();  // degrees, positive = tag is downward
double area  = target.getArea();   // % of frame area, useful for distance estimate

// ── All targets in this frame ─────────────────────────────────────────────
for (PhotonTrackedTarget t : result.getTargets()) {
    if (t.getFiducialId() == 7) {
        // Found tag 7 — process it
    }
}

// ── Timestamp — important for vision-odometry fusion ─────────────────────
double captureTimestamp = result.getTimestampSeconds();
// This is when the IMAGE WAS CAPTURED, not when your code received it.
// SwerveDrivePoseEstimator.addVisionMeasurement() needs this timestamp
// to correctly weight the measurement against historical odometry data.
💡 The timestamp is not the current time

result.getTimestampSeconds() returns when the image was captured by the camera, not when your code received the result. There is latency in the pipeline: image capture → coprocessor processing → NetworkTables transmission → roboRIO receive. This latency is typically 30–100 ms depending on the camera, resolution, and coprocessor. When you pass a vision measurement to SwerveDrivePoseEstimator.addVisionMeasurement(), you must pass this capture timestamp (not Timer.getFPGATimestamp()) so the estimator can correctly position the measurement in the robot's historical odometry trajectory. Passing the wrong timestamp is a silent correctness bug — the math looks right but the fusion weights are computed against the wrong odometry state.

Three Common PhotonVision Configuration Mistakes

These are the three mistakes that produce hard-to-diagnose failures — the code runs without errors but the robot doesn't behave correctly.

Mistake 1: Wrong camera name in robot code

new PhotonCamera("FrontCamera") must exactly match the name shown in PhotonVision's dashboard dropdown — including capitalization, spacing, and special characters. A mismatch produces a camera object that silently returns empty results. getLatestResult().hasTargets() always returns false. Check with SmartDashboard.putBoolean("Camera/Connected", m_camera.isConnected()) — if it returns false and the coprocessor is running, the name is wrong.

Mistake 2: No calibration, or calibration at wrong settings

An uncalibrated camera produces getBestCameraToTarget() transforms where the distance is systematically wrong. The camera detects tags and returns transforms, but every distance estimate is off by a consistent factor. If you compute robot poses from these and they're always too close to or too far from the tag's actual position, check the calibration. Verify the RMS error is shown in the Calibration tab and is below 0.5.

Mistake 3: Wrong tag family in the pipeline

If PhotonVision is configured for tag16h5 (a legacy family) but the field uses 36h11, the pipeline will either detect nothing at all or produce false positives from random dark patterns that accidentally match the smaller 4×4 bit grid. Verify the tag family in the pipeline settings: open the pipeline's configuration, find the "AprilTag Family" dropdown, and confirm it shows "TAG_36H11".

🔍 Using the PhotonVision dashboard during a match queue

The PhotonVision web dashboard is accessible during a match queue — you can open it from any laptop on the robot network, see the live camera feed, and verify tag detections. This is genuinely useful in the queue: point the camera at a known tag, confirm detections appear (green outlines in the stream), check the reported distance is reasonable, and verify the pipeline is set to the correct family and calibration. A 60-second dashboard check in the queue has found critical configuration problems before the match started. Make it a standard pre-match habit.

🔌 System Check

⚙️ Before Trusting PhotonVision in Autonomous

Work through this list before any match that relies on vision-based pose estimation:

  • Coprocessor is reachable at its static IP and the dashboard loads. Navigate to http://10.TE.AM.11:5800 (your team's IP) and confirm the dashboard loads and shows the camera stream. If it doesn't, the coprocessor either didn't boot or has a different IP — find it via the router before assuming a hardware failure.
  • Live camera stream shows the field view. Rotate the robot to face a tag. Confirm the stream updates and the tag is visible. If the stream shows nothing or a frozen frame, the camera connection to the coprocessor failed — re-seat the USB cable.
  • Tag detections appear as green outlines in the stream. Point the camera at a tag from 2–3 meters. Green corner dots or an outlined box should appear over the tag in the stream. No detection from this distance almost always means wrong tag family, bad calibration, or exposure too high (tag is washed out).
  • Robot code logs show detection data. Check SmartDashboard for Vision/HasTargets = true and Vision/TargetCount ≥ 1 when facing a tag. If these remain false while the dashboard shows detections, the camera name in robot code doesn't match the dashboard name.
  • Distance estimate is reasonable. At a measured 2.0 m from a tag, the reported distance from getBestCameraToTarget().getTranslation().getNorm() should read 1.9–2.1 m. More than 10% off means the calibration needs to be redone or the tag size constant is wrong.

Knowledge Check

1. A team's robot code uses new PhotonCamera("Front_Camera"). PhotonVision's dashboard shows the camera listed as "FrontCamera". SmartDashboard shows Vision/HasTargets always false, even when the dashboard stream clearly shows green tag outlines. What is the cause?

  • A The coprocessor and roboRIO are on different VLANs
  • B The camera name in Java ("Front_Camera") doesn't match the dashboard name ("FrontCamera") — the underscore makes them different strings; the Java code subscribes to a NetworkTables topic that doesn't exist, receiving empty results
  • C PhotonLib version is incompatible with the firmware
  • D getLatestResult() can only be called once per second

2. A team calibrates their camera at 640×480 resolution with auto-exposure on, then switches to 1280×720 with a fixed 3 ms exposure for competition. They don't recalibrate. What will happen to their pose estimates?

  • A No effect — camera calibration is resolution-independent
  • B The calibration's intrinsic parameters (focal length in pixels, principal point) were computed for 640×480 pixel coordinates but the pipeline now produces 1280×720 pixel coordinates — solvePnP will compute systematically wrong poses because it's using the wrong pixel-to-angle mapping
  • C The calibration automatically scales with resolution
  • D Only the distortion coefficients are affected; translation estimates will still be correct

3. When passing a vision measurement to SwerveDrivePoseEstimator.addVisionMeasurement(), which timestamp should be used, and why?

  • A Timer.getFPGATimestamp() — this is the most accurate time source available on the roboRIO
  • B result.getTimestampSeconds() — this is when the image was captured (before pipeline processing and NetworkTables latency), which is the moment in time the vision measurement actually reflects the robot's position; using the current time would tell the estimator to match this vision pose against a more recent odometry state, corrupting the fusion
  • C The average of the FPGA timestamp and the result timestamp to account for transmission latency
  • D Any timestamp works because the pose estimator ignores timestamps for vision measurements
💪 Practice Prompt

Get PhotonVision Running and Verify Tag Detection End-to-End

  1. Flash PhotonVision onto your coprocessor. Assign it a static IP in the 10.TE.AM.11 range from the Settings tab. Confirm you can load the web dashboard from your laptop over the robot network. Document the static IP in your team's pit guide alongside the coprocessor's MAC address (useful if you ever need to identify it on a router).
  2. Create an AprilTag pipeline named "AprilTagPipeline" in PhotonVision. Set the tag family to TAG_36H11, disable auto-exposure, and set a fixed exposure between 2–6 ms. Hold an AprilTag in front of the camera and verify that green detection outlines appear in the stream. Take a screenshot of the stream with a detected tag for your records.
  3. Perform camera calibration: print a chessboard at 100% scale, confirm the square size with a ruler, capture 30+ images from varied angles and distances in PhotonVision's Calibration tab, and run calibration. Record the RMS error. If it's above 0.5, recapture with sharper images and better angle diversity. Save the calibration.
  4. Add PhotonLib to your robot project. Create a VisionSubsystem with a PhotonCamera using the exact name from your dashboard. In periodic(), call getLatestResult() and publish hasTargets() and getTargets().size() to SmartDashboard. Deploy and verify these values update in real time when you hold a tag in view.
  5. Bonus: At exactly 2.0 m from a tag (measured with a tape measure), log getBestCameraToTarget().getTranslation().getNorm() to SmartDashboard. Record the reported distance. Repeat at 1.0 m and 3.0 m. Calculate the percentage error at each distance. A well-calibrated camera should be within ±5% at all three distances. If the error is larger or grows nonlinearly with distance, the calibration needs to be redone.