Hi,
We already have a pipeline working with opencv calibration and computing depth of the objects via triangulation(opencv). But, we’re just using zed as stereo camera and not using it’s fancy features. We were thinking if we use the depth map feature we’re going to make our pipeline much much simpler. Atm moment we’re not able to use ZED calibration tool since our cameras have to be under water and ZED tools need some monitor attached to it to work properly (tried with vnc already not working). Therefore we went into the route of exploring and applying our already ready opencv calibrations applying them to zed at the start and just getting already undistorted/rectified images with depth info. The task seemed easy but we’re not getting very good results.
The object is at 66cm distance and when :
- We use no calibration just factory settings the depth measured is around 50cm.
- We use our opencv calibration the depth measured is aroud 100cm.
We’re following the guide here : How to Calibrate your ZED camera with OpenCV - Stereolabs
This is our calibration code :
# Calibrating left camera with standard model (extended flags cause numerical instability with ZED constraints)
retL, mtxL, distL, _, _ = cv2.calibrateCamera(
obj_pts, img_ptsL, (parameters["width"], parameters["height"]), None, None
)
# Calibrating right camera with standard model
retR, mtxR, distR, _, _ = cv2.calibrateCamera(
obj_pts, img_ptsR, (parameters["width"], parameters["height"]), None, None
)
flags = 0
# Use ZED guide recommended flags for stereo calibration
flags |= cv2.CALIB_FIX_ASPECT_RATIO
flags |= cv2.CALIB_USE_INTRINSIC_GUESS
flags |= cv2.CALIB_ZERO_TANGENT_DIST
flags |= cv2.CALIB_SAME_FOCAL_LENGTH
# Here we fix the intrinsic camara matrixes so that only Rot, Trns, Emat and Fmat are calculated.
# Hence intrinsic parameters are the same
# This step is performed to transformation between the two cameras and calculate Essential and Fundamenatl matrix
rms, mtxL, distL, mtxR, distR, Rot, Trns, _, _ = cv2.stereoCalibrate(
obj_pts, img_ptsL, img_ptsR, mtxL, distL, mtxR, distR, original_size, criteria=criteria, flags=flags
)
Then I have this conversion code to zed yaml :
def convert_calibration_json_to_zed_yaml(
calibration_json: str, image_width: int, image_height: int, logger=None
) -> str:
"""
Convert calibration parameters from JSON format to ZED SDK YAML format.
R and T used if available already
Args:
calibration_json: JSON string containing calibration parameters
image_width: Image width in pixels
image_height: Image height in pixels
logger: Optional logger instance for debugging information
Returns:
Path to temporary YAML file compatible with ZED SDK
Raises:
ValueError: If required calibration parameters are missing
"""
try:
calib_data = json.loads(calibration_json)
except json.JSONDecodeError as e:
raise ValueError(f"Invalid JSON in calibration data: {e}")
# Validate required parameters
required_params = ["mtxL", "mtxR", "distL", "distR", "projMatL", "projMatR"]
missing_params = [param for param in required_params if param not in calib_data]
if missing_params:
raise ValueError(f"Missing required calibration parameters: {missing_params}")
# Convert to numpy arrays for calculations
mtxL = np.array(calib_data["mtxL"], dtype=np.float64)
mtxR = np.array(calib_data["mtxR"], dtype=np.float64)
distL = np.array(calib_data["distL"], dtype=np.float64).flatten()
distR = np.array(calib_data["distR"], dtype=np.float64).flatten()
projMatL = np.array(calib_data["projMatL"])
projMatR = np.array(calib_data["projMatR"])
# Validate matrix dimensions
if mtxL.shape != (3, 3) or mtxR.shape != (3, 3):
raise ValueError("Camera matrices must be 3x3")
if projMatL.shape != (3, 4) or projMatR.shape != (3, 4):
raise ValueError("Projection matrices must be 3x4")
# Preserve full distortion coefficients (pad to at least 5, up to 12 for extended models)
# Don't truncate - ZED SDK can handle up to 12 coefficients
target_length = max(5, len(distL), len(distR), 12) # Support extended distortion models
if len(distL) < target_length:
distL = np.pad(distL, (0, target_length - len(distL)), "constant")
if len(distR) < target_length:
distR = np.pad(distR, (0, target_length - len(distR)), "constant")
# Check if projection matrices appear to be rectified
# For non-rectified stereo: projMatL should be approximately K_LEFT * [I|0]
expected_projMatL = mtxL @ np.hstack([np.eye(3), np.zeros((3, 1))])
if not np.allclose(projMatL, expected_projMatL, atol=1e-6):
warnings.warn(
"Projection matrices appear to be rectified (projMatL != K_LEFT * [I|0]). "
"The recovered R and T will be rectified extrinsics, not raw physical camera extrinsics. "
"ZED SDK expects original camera extrinsics for optimal performance.",
UserWarning,
)
# Use rRaw and tRaw directly if available, otherwise calculate from projection matrices
if "rRaw" in calib_data and "tRaw" in calib_data:
if logger:
logger.info("Using rRaw and tRaw matrices directly from calibration data")
R = np.array(calib_data["rRaw"], dtype=np.float64)
T = np.array(calib_data["tRaw"], dtype=np.float64)
# Validate dimensions
if R.shape != (3, 3):
raise ValueError("rRaw must be a 3x3 matrix")
if T.shape not in [(3, 1), (1, 3)]:
raise ValueError("tRaw must be a 3x1 or 1x3 matrix")
# Ensure T is column vector (3x1)
if T.shape == (1, 3):
T = T.T
else:
if logger:
logger.info("Calculating R and T from projection matrices (rRaw/tRaw not available)")
# Calculate R and T from projection matrices
R, T = calculate_stereo_transform_from_projection_matrices(projMatL, projMatR, mtxL, mtxR)
# Create temporary file and write using OpenCV FileStorage
fd, temp_path = tempfile.mkstemp(suffix=".yml", prefix="zed_custom_calib_")
os.close(fd) # Close file descriptor since we'll use OpenCV FileStorage
try:
# Use OpenCV FileStorage to generate proper !!opencv-matrix tags
fs = cv2.FileStorage(temp_path, cv2.FILE_STORAGE_WRITE)
# Write image size
fs.write("Size", np.array([image_width, image_height], dtype=np.int32))
# Write camera matrices and distortion coefficients
fs.write("K_LEFT", mtxL)
fs.write("D_LEFT", distL.reshape(1, -1))
fs.write("K_RIGHT", mtxR)
fs.write("D_RIGHT", distR.reshape(1, -1))
# Write rotation and translation
fs.write("R", R)
fs.write("T", T.reshape(3, 1))
fs.release()
# Read the generated file content to return as string
with open(temp_path, "r") as f:
yaml_content = f.read()
# Post-process Size to simple list form expected by ZED SDK
try:
# Handle both 1x2 and 2x1 matrix formats for Size
size_pattern = re.compile(
r"(?ms)^Size:\s*!!opencv-matrix\s*\n\s*rows:\s*[12]\s*\n\s*cols:\s*[12]\s*\n\s*dt:\s*[ifd]\s*\n\s*data:\s*\[\s*([0-9]+)\s*,\s*([0-9]+)\s*\]\s*"
)
yaml_content = size_pattern.sub(r"Size: [ \1, \2 ]\n", yaml_content)
except Exception:
# Non-fatal; leave original if substitution fails
pass
# Clean up temporary file
os.unlink(temp_path)
return yaml_content
except Exception as e:
# Clean up on error
if os.path.exists(temp_path):
os.unlink(temp_path)
raise ValueError(f"Failed to generate calibration YAML: {e}")
Looks like the things are loaded and ZED is not complaining :
| 2025-09-18 14:27:44,818 - info - zedcamera - === raw calibration json ===
| 2025-09-18 14:27:44,819 - info - zedcamera - calibration json:
| {
| "mtxl": [
| [
| 1694.7538664405201,
| 0.0,
| 982.2363730503921
| ],
| [
| 0.0,
| 1697.9051963872203,
| 592.583839567283
| ],
| [
| 0.0,
| 0.0,
.0
| ]
| ],
| "mtxR": [
| [
| 1694.7538664405201,
| 0.0,
| 995.350180031674
| ],
| [
| 0.0,
| 1697.9051963872203,
| 593.3354905377101
| ],
| [
| 0.0,
| 0.0,
.0
| ]
| ],
| "distL": [
| [
| 0.3887216657192178,
| 0.04782106468726986,
| -0.00584037852906406,
| -0.006571833932916075,
| 0.6110652860987891
| ]
| ],
| "distR": [
| [
| 0.368297530619768,
| 0.2809492456906151,
| -0.005883451112045473,
| -0.000426228998142811,
| 0.006297223798803174
| ]
| ],
| "projMatL": [
| [
| 1694.7538664405201,
| 0.0,
| 982.2363730503921,
| 0.0
| ],
| [
| 0.0,
| 1697.9051963872203,
| 592.583839567283,
| 0.0
| ],
| [
| 0.0,
| 0.0,
.0,
| 0.0
| ]
| ],
| "projMatR": [
| [
| 1702.941043264309,
| 0.28462830580805676,
| 981.2769083478794,
| -84419.33301837795
| ],
| [
| 4.718349358469729,
| 1697.9585252843942,
| 593.1640952078328,
| 3.876135024387207
| ],
| [
| 0.008283856579695662,
| 8.991037252593722e-05,
| 0.9999656842293599,
| -0.24858776968380142
| ]
| ],
| "rRaw": [
| [
| 0.99996568155688,
| 0.00011514120380058085,
| -0.008283866910300251
| ],
| [
| -0.00011588205820130007,
| 0.999999989329314,
| -8.895347372323467e-05
| ],
| [
| 0.008283856579695662,
| 8.991037252593722e-05,
| 0.9999656842293599
| ]
| ],
| "tRaw": [
| [
| -49.66615082215754
| ],
| [
| 0.08915225750736161
| ],
| [
| -0.24858776968380142
| ]
| ]
| }
| 2025-09-18 14:27:44,819 - INFO - zedcamera - === End Raw Calibration JSON ===
| 2025-09-18 14:27:44,821 - INFO - zedcamera - Using custom calibration:
| Custom ZED Calibration Summary:
| Left Camera:
| - Focal Length: fx=1694.8, fy=1697.9
| - Principal Point: cx=982.2, cy=592.6
| Right Camera:
| - Focal Length: fx=1694.8, fy=1697.9
| - Principal Point: cx=995.4, cy=593.3
| Stereo:
| - Baseline: 49.7 mm
| 2025-09-18 14:27:44,822 - INFO - zed_calibration_utils - Using rRaw and tRaw matrices directly from calibration data
| 2025-09-18 14:27:44,830 - INFO - zedcamera - === YAML Calibration Content ===
| 2025-09-18 14:27:44,830 - INFO - zedcamera - YAML content:
.0
| ---
| Size: [ 1920, 1200 ]
| K_LEFT: !!opencv-matrix
| rows: 3
| cols: 3
| dt: d
.6947538664405201e+03, 0., 9.8223637305039210e+02, 0.,
.6979051963872203e+03, 5.9258383956728301e+02, . ]
| D_LEFT: !!opencv-matrix
| cols: 5
| dt: d
| data: [ 3.8872166571921779e-01, 4.7821064687269862e-02,
| -5.8403785290640602e-03, -6.5718339329160751e-03,
| 6.1106528609878907e-01 ]
| K_RIGHT: !!opencv-matrix
| rows: 3
| cols: 3
| dt: d
.6947538664405201e+03, 0., 9.9535018003167397e+02, 0.,
.6979051963872203e+03, 5.9333549053771014e+02, . ]
| D_RIGHT: !!opencv-matrix
| cols: 5
| dt: d
| data: [ 3.6829753061976800e-01, 2.8094924569061508e-01,
| -5.8834511120454732e-03, -4.2622899814281098e-04,
| 6.2972237988031740e-03 ]
| R: !!opencv-matrix
| rows: 3
| cols: 3
| dt: d
| data: [ 9..1514120380058085e-04,
| -8.2838669103002509e.1588205820130007e-04,
| 9.9999998932931400e-01, -8.8953473723234672e-05,
| 8.2838565796956622e-03, 8.9910372525937220e-05,
| 9.9996568422935994e-01 ]
| T: !!opencv-matrix
| rows: 3
| dt: d
| data: [ -4.9666150822157540e+01, 8.9152257507361610e-02,
| -2.4858776968380142e-01 ]
|
| 2025-09-18 14:27:44,830 - INFO - zedcamera - === End YAML Content ===
| 2025-09-18 14:27:44,830 - INFO - zedcamera - Disabled ZED self-calibration (custom calibration provided)
| 2025-09-18 14:27:44,830 - INFO - zedcamera - Custom calibration file created: /tmp/zed_custom_calib_uc986kfu.yml
| 2025-09-18 14:27:44,830 - INFO - zedcamera - Opening ZED Camera...
| [2025-09-18 14:27:44 UTC][ZED][INFO] Logging level INFO
| [2025-09-18 14:27:44 UTC][ZED][INFO] Logging level INFO
| [2025-09-18 14:27:44 UTC][ZED][INFO] Logging level INFO
| [2025-09-18 14:27:44 UTC][ZED][INFO] [Init] Depth mode: ULTRA
| [2025-09-18 14:27:46 UTC][ZED][INFO] [Init] Camera FW version: 2001
| [2025-09-18 14:27:46 UTC][ZED][INFO] [Init] Video mode: HD1200@15
I’m applying the file with optional_opencv_calibration_file
I know the calibration is kind of ok because our current pipeline measures it correctly (67cm). Are we doing something wrong or is it that Zed depth is not suitable for that kind of distance. Any ideas are welcome.