retinify 0.1.7
Real-Time AI Stereo Vision Library
Loading...
Searching...
No Matches
Calibration

Calibration Parameters

retinify::CalibrationParameters supports the pinhole camera model.

Loading Calibration Parameters

retinify::CalibrationParameters can be loaded directly from a JSON file as follows:

Sample Stereo Calibration JSON

This JSON file defines stereo camera calibration parameters.

{
// Reprojection error after calibration (optional)
"calibration_error": 0.0,
// Calibration timestamp or duration (optional)
"calibration_time": 0,
// Image resolution used for calibration
"image_width": 1241,
"image_height": 376,
// Left camera intrinsics
"left_intrinsics": {
"fx": 718.856,
"fy": 718.856,
"cx": 607.1928,
"cy": 185.2157,
"skew": 0.0
},
// Right camera intrinsics
"right_intrinsics": {
"fx": 718.856,
"fy": 718.856,
"cx": 607.1928,
"cy": 185.2157,
"skew": 0.0
},
// Left camera distortion coefficients
"left_distortion": {
"k1": 0.0,
"k2": 0.0,
"k3": 0.0,
"k4": 0.0,
"k5": 0.0,
"k6": 0.0,
"p1": 0.0,
"p2": 0.0
},
// Right camera distortion coefficients
"right_distortion": {
"k1": 0.0,
"k2": 0.0,
"k3": 0.0,
"k4": 0.0,
"k5": 0.0,
"k6": 0.0,
"p1": 0.0,
"p2": 0.0
},
// Rotation matrix
"rotation": [
[1.0, 0.0, 0.0],
[0.0, 1.0, 0.0],
[0.0, 0.0, 1.0]
],
// Translation vector
"translation": [-0.5371657, 0.0, 0.0]
}

// Load calibration parameters from JSON file
retinify::LoadCalibrationParameters("calib.json", calib_params);
// Initialize pipeline with calibration parameters
pipeline.Initialize(image_width,
image_height,
calib_params);
A retinify::Pipeline provides an interface for running a stereo matching.
Definition pipeline.hpp:46
auto Initialize(std::uint32_t imageWidth, std::uint32_t imageHeight, PixelFormat pixelFormat=PixelFormat::RGB8, DepthMode depthMode=DepthMode::ACCURATE, const CalibrationParameters &calibrationParameters=CalibrationParameters{}) noexcept -> Status
Initializes the stereo matching pipeline with the given image dimensions.
@ RGB8
8-bit 3ch, RGB format
@ ACCURATE
Most accurate, with slowest performance.
RETINIFY_API auto LoadCalibrationParameters(const char *filename, CalibrationParameters &parameters) noexcept -> Status
Load stereo calibration parameters.
Stereo camera calibration parameters.
Definition geometry.hpp:266