Eye-in-hand calibration determines the rigid transform between the wrist camera and the robot’s tool flange (Documentation Index
Fetch the complete documentation index at: https://mintlify.com/MRRP-lab/arm-demos/llms.txt
Use this file to discover all available pages before exploring further.
tool0). Once you have this transform, you can express any point the camera sees directly in the robot’s base frame — a prerequisite for reliable vision-guided manipulation. The calibration workflow is split into two scripts: eye_in_hand.py for interactive data collection and hand_eye_solve.py for computing the transform.
Overview
eye_in_hand.py
Runs a ROS 2 node that reads TF2 transforms and saves pose samples to
calib_samples.npz as you move the arm to different poses.hand_eye_solve.py
Loads the saved samples and runs five OpenCV hand-eye calibration methods, then prints URDF
<origin> tags for each result.Calibration procedure
Mount the camera on the wrist
Attach the OAK-D Pro camera to the UR3e wrist mount so it is rigidly fixed relative to
tool0. Any movement between captures will corrupt the calibration.Place the AprilTag target
Fix an AprilTag 36h11 marker with ID
tag_20 in a stationary location within the camera’s field of view. The tag must remain completely still during the entire data collection session.Start bringup
Bring up the robot driver,
ros2_control, and the AprilTag detection node so that TF2 frames for tag_20 and tool0 are being published:Move the arm and capture samples
Jog the arm to a new pose (different height, rotation, and distance from the tag). When the arm is still, press Enter to capture the sample. The node looks up two TF2 transforms:Repeat for at least 10–15 distinct poses.
base_link→tool0(arm end-effector pose)oakd_pro_camera_rgb_optical_frame_wrist→tag_20(tag in camera frame)
capture() method records both:Save the samples
Press
q and Enter. The node saves all samples to calib_samples.npz in the current working directory and shuts down.Run the solver
hand_eye_solve.py loads calib_samples.npz and runs five calibration methods:<origin> tag:Update the URDF
Compare the five outputs. They should agree to within a few millimetres in translation and a few tenths of a degree in rotation. If they diverge significantly, collect more diverse samples and re-run.Copy the result (TSAI or the average) into the camera mount Rebuild the workspace after editing the URDF:
<joint> in your URDF xacro:TF2 frames used
| Frame | Description |
|---|---|
base_link | Robot base (world anchor) |
tool0 | Robot tool flange (end-effector) |
oakd_pro_camera_rgb_optical_frame_wrist | Camera optical frame (published by the OAK-D driver) |
tag_20 | AprilTag 36h11, ID 20 (published by the AprilTag node) |
Saved data format
calib_samples.npz contains four arrays, each with one entry per captured pose:
| Key | Shape | Description |
|---|---|---|
arm_rotations | (N, 3, 3) | Rotation matrices for base_link → tool0 |
arm_translations | (N, 3, 1) | Translation vectors for base_link → tool0 |
tag_rotations | (N, 3, 3) | Rotation matrices for camera → tag_20 |
tag_translations | (N, 3, 1) | Translation vectors for camera → tag_20 |
Keep
calib_samples.npz alongside hand_eye_solve.py, or pass the path explicitly if you run the solver from a different directory.