Eye-in-hand robot calibration and workspace localization.
Mount a camera on your robot's end-effector, run a one-time calibration, and then at runtime eyehand tells you where AprilTag markers are in the robot's coordinate frame. That's it.
It works with any robot that can report its joint positions (FK), any USB or depth camera, and doesn't need ROS.
There are three steps. You do the first two once, then repeat the third in your runtime loop:
-
Calibrate the camera — Show a printed ChArUco checkerboard to the camera from ~20 angles. eyehand estimates the camera's lens properties (focal length, distortion). Takes a few minutes.
-
Calibrate the hand-eye transform — Move the robot to ~15 diverse poses while the camera sees the checkerboard. eyehand figures out exactly where the camera sits relative to the robot's wrist. Also a few minutes.
-
Locate objects — At runtime, point the camera at AprilTag markers in your workspace. eyehand combines the camera image, the robot's current joint pose, and both calibration results to report each tag's position in the robot base frame.
Steps 1 and 2 each produce a small JSON file. Step 3 loads those files and runs in a loop.
pip install -e .Requires Python 3.10+ and these dependencies:
| Package | Version | Why |
|---|---|---|
| numpy | >=1.26 | Array math |
| scipy | >=1.16 | Rotation conversions |
| opencv-contrib-python | >=4.7,<4.12 | ChArUco detection (needs the -contrib variant, not plain opencv-python) |
| pupil-apriltags | >=1.0.4 | AprilTag detection |
- A camera mounted on the robot's end-effector (USB webcam, Luxonis OAK-D, etc.)
- A printed ChArUco board for calibration (generate a PDF with
python -m eyehand.scripts.generate_board) - Printed AprilTags (tag36h11 family) placed in your workspace (generate a PDF with
python -m eyehand.scripts.generate_tags) - A ruler or calipers to measure the tag size and board square size in metres -- measurement accuracy directly affects results
Run the full pipeline with synthetic data to see how everything fits together:
python -m eyehand.scripts.demoThis generates synthetic board images, calibrates intrinsics and hand-eye, then localizes simulated AprilTags -- all in a few seconds. The output includes calibration JSON files you can inspect.
First, generate and print a ChArUco board (skip if you already have one):
python -m eyehand.scripts.generate_board -o board.pdfDefaults to a 5×7 board at 36 mm squares / 27 mm markers, centered on a US Letter page (--paper letter). Pass --paper a4 for A4, or --paper none to crop the page tightly to the board. Print at 100% scale / "actual size" (not "fit to page"), then measure a square with calipers to confirm it is 36 mm.
Printer scale compensation. Many office printers (notably the HP LaserJet M110/M111/M112 series) silently shrink printed pages by ~5.6% even when the print dialog says "100%". The script compensates by default using
--printer-scale 0.9444, oversizing the internal board so the printed output matches your requested--square-length. If you measure the printed square and it's wrong, computemeasured_mm / target_mmand pass that as--printer-scale, or pass--printer-scale 1.0to disable compensation entirely for a dimensionally faithful printer. Either way, the authoritative value you put into--square-length(and intoCharucoDetector(square_length=…)) is whatever your calipers read.
Then run the calibration script. Live webcam mode (default) opens a window — show the board to the camera from many angles, press SPACE to capture each view and ENTER when you have at least 15:
python -m eyehand.scripts.calibrate_intrinsics # default webcam (index 0)
python -m eyehand.scripts.calibrate_intrinsics --webcam 1 # alternate webcam
python -m eyehand.scripts.calibrate_intrinsics --images calib_images/ # pre-captured jpg/png/bmpPass the actual measured board dimensions if they differ from the defaults:
python -m eyehand.scripts.calibrate_intrinsics --square-length 0.034 --marker-length 0.0255The script writes intrinsics.json (override with -o) and prints the RMS reprojection error plus a quality-gate verdict (PASS = every per-view error below 0.5 px). If the gate fails, recapture with more pose variety, sharper focus, or better lighting and re-run.
If you'd rather drive intrinsic calibration from your own code (e.g. inside an existing capture pipeline), the underlying API is eyehand.calibration.intrinsics.IntrinsicCalibrator — see docs/usage_guide.md for the Python equivalent.
Move the robot to ~15 diverse poses while the camera sees the ChArUco board:
from eyehand import PoseCollector, HandEyeCalibrator, CalibrationStore
collector = PoseCollector()
# Move robot, capture board detections + FK poses until coverage is sufficient
# PoseCollector.is_ready() returns True when you have enough diverse poses
# See docs/usage_guide.md for the full collection loop
calibrator = HandEyeCalibrator()
result = calibrator.calibrate(
R_gripper2base, t_gripper2base,
R_target2cam, t_target2cam,
)
# Save for later — this file captures where the camera sits on the wrist
CalibrationStore.save_hand_eye(Path("hand_eye.json"), result)Load both calibration files and run in a loop:
from pathlib import Path
from eyehand import WorkspaceLocalizer, CalibrationStore, AprilTagDetector
# Load the two calibration files from steps 1 and 2
hand_eye = CalibrationStore.load_hand_eye(Path("hand_eye.json"))
intrinsics = CalibrationStore.load_intrinsics(Path("intrinsics.json")).intrinsics
# Create the localizer once
localizer = WorkspaceLocalizer(
hand_eye=hand_eye,
detector=AprilTagDetector(tag_size=0.05), # tag side length in metres
intrinsics=intrinsics,
)
# Runtime loop
result = localizer.localize(camera.capture(), robot.get_ee_pose())
for tag_id, pose in result.tag_poses.items():
print(f"Tag {tag_id}: {pose.position} m (robot base frame)")
# result.ambiguous_ids lists tags seen at bad angles — filter them out
reliable = {k: v for k, v in result.tag_poses.items()
if k not in result.ambiguous_ids}Note:
robot.get_ee_pose()must return the end-effector pose in the robot base frame (T_ee_in_base) — the standard FK convention.
eyehand includes scripts for common setup tasks. Run any with --help for full options.
Generate a printable ChArUco board for camera calibration (PDF by default, centered on US Letter):
python -m eyehand.scripts.generate_board -o board.pdf
python -m eyehand.scripts.generate_board --paper a4 -o board.pdf
python -m eyehand.scripts.generate_board --squares-x 5 --squares-y 7 --square-length 0.036 --marker-length 0.027 -o board.pdf
python -m eyehand.scripts.generate_board -o board.png # PNG outputCalibrate camera intrinsics from a webcam or a directory of board images:
python -m eyehand.scripts.calibrate_intrinsics # default webcam, save intrinsics.json
python -m eyehand.scripts.calibrate_intrinsics --webcam 1
python -m eyehand.scripts.calibrate_intrinsics --images calib_images/ -o intrinsics.json
python -m eyehand.scripts.calibrate_intrinsics --square-length 0.034 --marker-length 0.0255Generate printable AprilTag images for workspace markers:
python -m eyehand.scripts.generate_tags -o tags.pdf
python -m eyehand.scripts.generate_tags --ids 0-9 --tag-size 0.04 -o tags.pdf
python -m eyehand.scripts.generate_tags --paper a4 --ids 0,3,7 -o tags.pdfDefaults to a 0-4 range of 50 mm tags, laid out in a grid on a US Letter page with ID N captions under each tag, printer-scale compensated (same --printer-scale 0.9444 default as generate_board). Multi-page PDFs are produced automatically when more tags are requested than fit on one sheet.
Locate AprilTags from a webcam (live overlay) or a single image — no robot needed:
python -m eyehand.scripts.locate_tags # default webcam, intrinsics.json
python -m eyehand.scripts.locate_tags --webcam 1 --tag-size 0.04
python -m eyehand.scripts.locate_tags --image photo.png # single-shot, prints to terminal
python -m eyehand.scripts.locate_tags --csv # machine-readable outputInspect a calibration file to check what's inside without writing code:
python -m eyehand.scripts.inspect_calibration intrinsics.json
python -m eyehand.scripts.inspect_calibration hand_eye.jsoneyehand is arranged in layers. Each layer only imports from layers below it:
Localization — combines everything into base-frame tag positions
Calibration — camera intrinsics, hand-eye transform, persistence
Detection — ChArUco board + AprilTag detection
Interfaces — robot/camera abstractions (swap in mocks for testing)
Transforms — SE(3) math, Pose type, frame chains
All public symbols are re-exported from the top-level eyehand package.
- Usage Guide — full pipeline walkthrough with complete code for each step
- Calibration Tips — best practices for good calibration quality
MIT