Camera Calibration Overview Camera parameters such as focal length, field of view or stereo calibration can be retrieved for each eye and resolution: Focal length: fx, fy. Principal points: cx, cy. Lens distortion: k1, k2, k3, p1, p2. Horizontal, vertical and diagonal field of view. Stereo calibration: rotation and translation between left and right eye. Using the API Camera parameters are available in CalibrationParameters. They can be retrieved using getCameraInformation(). C++ Python C# CalibrationParameters calibration_params = zed.getCameraInformation().camera_configuration.calibration_parameters; // Focal length of the left eye in pixels float focal_left_x = calibration_params.left_cam.fx; // First radial distortion coefficient float k1 = calibration_params.left_cam.disto[0]; // Translation between left and right eye on z-axis float tz = calibration_params.T.z; // Horizontal field of view of the left eye in degrees float h_fov = calibration_params.left_cam.h_fov; calibration_params = zed.get_camera_information().camera_configuration.calibration_parameters # Focal length of the left eye in pixels focal_left_x = calibration_params.left_cam.fx # First radial distortion coefficient k1 = calibration_params.left_cam.disto[0] # Translation between left and right eye on z-axis tz = calibration_params.T.z # Horizontal field of view of the left eye in degrees h_fov = calibration_params.left_cam.h_fov CalibrationParameters calibration_params = zed.GetCalibrationParameters(); // Focal length of the left eye in pixels float focal_left_x = calibration_params.leftCam.fx; // First radial distortion coefficient float k1 = calibration_params.leftCam.disto[0]; // Translation between left and right eye on z-axis float tz = calibration_params.Trans.z; // Horizontal field of view of the left eye in degrees float h_fov = calibration_params.leftCam.hFOV; Note: If self-calibration is enabled, calibration parameters can be re-estimated and refined by the ZED SDK at startup. Updated parameters will be available in CalibrationParameters. Calibration Tool It is possible to recalibrate your camera manually using the ZED Calibration tool. However, we do not recommend this for ZED 2 cameras. They go through extensive and rigorous multi-step factory calibration (including thermal measurements), and a manual calibration might degrade its calibration parameters.