1 # Copyright (c) 2019-2020 NVIDIA CORPORATION. All rights reserved.
3 @page stereo_usecase1 Disparity Computation Workflow
5 This section explains how to use NVIDIA<sup>®</sup> DriveWorks Stereo Rectifier and Stereo to rectify two images of a stereo pair and compute a disparity map from them.
6 The stereo disparity algorithm is based on a pair of Gaussian pyramids represented by two `::dwPyramidImage` objects that are built from a pair of rectified `dwImageCUDA` images.
8 ### Step 1: Obtain the intrinsic and extrinsic camera parameters for the left and right camera
9 Before you can initialize the stereo rectifier, you must first obtain the intrinsic and extrinsic camera parameters for the left and right camera.
11 The camera intrinsics encompass data such as focal length and principal point.
12 The intrinsic parameters of each camera are represented by a `::dwCameraModelHandle_t` object. They can be obtained from the rig configuration as follows:
15 // Initialize left and right calibrated cameras containing the camera intrinsic parameters
16 dwCameraModelHandle_t cameraModelLeft, cameraModelRight;
17 dwCameraModel_initialize(&cameraModelLeft, leftCamera_ID, rigConfigurationHandle);
18 dwCameraModel_initialize(&cameraModelRight, rightCamera_ID, rigConfigurationHandle);
21 where `rigConfigurationHandle` is a previously initialized `::dwRigHandle_t`; for more information on rig configuration see @ref rig_mainsection.
22 `leftCamera_ID` and `rightCamera_ID` are the corresponding known camera IDs in the rig file.
24 The camera extrinsics encompass the misalignment of the camera with respect to the rig in terms of rotation and translation.
25 The extrinsic parameters of each camera are represented by a `dwTransformation` object. They can be obtained from the rig configuration as follows:
28 // Get left and right camera extrinsic parameters from rig configuration
29 dwTransformation3f left2Rig, right2Rig;
30 dwRig_getSensorToRigTransformation(&left2Rig, leftCamera_ID , rigConfigurationHandle);
31 dwRig_getSensorToRigTransformation(&right2Rig, rightCamera_ID, rigConfigurationHandle);
34 ### Step 2: Initialize the stereo rectifier and the stereo handle
35 Once intrinsic and extrinsic parameters of both cameras are available, you can initialize the stereo rectifier handle `::dwStereoRectifierHandle_t` as follows:
38 // initialize stereo rectifier with intrinsic and extrinsic camera parameters
39 dwStereoRectifierHandle_t stereoRectifier;
40 dwStereoRectifier_initialize(stereoRectifier, cameraModelLeft, cameraModelRight, left2Rig, right2Rig, contextHandle);
43 where `contextHandle` is a previously initialized `::dwContextHandle_t`.
45 To initialize a `::dwStereoHandle_t` object, only `dwStereoParams` is required. For example, the following example initializes stereo parameters with default values:
48 dwStereoParams stereoParams{};
49 dwStereo_initParams(stereoParams);
52 And the following modifies the parameters according to application requirements:
55 // initialize some stereo parameters
56 stereoParams.side = side;
57 stereoParams.levelCount = levelCount;
58 stereoParams.levelStop = levelStop;
61 For more information regarding all available parameters, please refer to the `dwStereoParams` struct.
63 @note The effects due to different settings of the following `dwStereoParams` parameters might be of special interest for the user:
64 - `levelCount`: A larger value leads the algorithm to work at higher pyramid levels, which implies a larger context size but possibly more matching ambiguity due to loss of detail.
65 - `maxDisparityRange`: Smaller values can speed up the algorithm.
66 - `refinementLevel`: A high refinement level will lead to a smoother disparity map.
67 - `initType`: In general, it is advisable to always try several cost types, as their performance is dependent on the image content.
69 After initializing the stereo parameters, initialize the module as follows:
72 // initialize stereo module
73 dwStereoHandle_t stereoAlgorithm;
74 dwStereo_initialize(stereoAlgorithm, imageWidth, imageHeight, stereoParams, contextHandle);
77 where `contextHandle` is assumed to be a previously initialized `::dwContextHandle_t`.
80 ### Step 3: Retrieve the rectangular ROI shared by both images
81 The rectification process applies a geometric transformation that projects the two images onto a common image plane.
82 This plane contains a rectangular region that is shared by both images after rectification, graphically represented by the magenta boxes in the @ref stereo_module_image "module diagram". It is represented by a `::dwBox2D` object, which can be retrieved as follows:
85 // Get resolution of output rectified images
87 dwStereoRectifier_getCropROI(&roi, stereoRectifier);
90 ### Step 4: Create output images for the rectification process
91 The knowledge of the region `roi` shall be used when creating the output images that will be passed to the rectification process. An example of this is given in the following snippet:
94 // Define image properties
95 dwImageProperties propsInput = imageProperties;
96 propsInput.type = DW_IMAGE_CUDA;
97 propsInput.format = DW_IMAGE_FORMAT_RGBA_UINT8;
99 // Set width and height according to roi
100 propsInput.width = roi.width;
101 propsInput.height = roi.height;
103 // Create output images
104 dwImageHandle_t outputRectifiedLeft, outputRectifiedRight;
105 dwImage_create(&outputRectifiedLeft, propsInput, contextHandle);
106 dwImage_create(&outputRectifiedRight, propsInput, contextHandle);
109 where `imageProperties` are known input image properties. Furthermore, you could use `roi` when creating image streamers for visualization purposes.
111 ### Step 5: At runtime, call the stereo rectification process
112 Execute the rectification process by calling `dwStereoRectifier_rectify()`.
113 In the following snippet, `stereoImageLeft` and `stereoImageRight` must have been obtained
114 from two input videos or a single stereo camera.
117 // CODE: Get left and right frames, stereoImageLeft and stereoImageRight, as dwImageCUDA from two input videos or from a stereo camera
119 // Rectify pair of images
120 dwStereoRectifier_rectify(outputRectifiedLeft, outputRectifiedRight, stereoImageLeft, stereoImageRight, stereoRectifier));
123 where `outputRectifiedLeft` and `outputRectifiedRight` now contain the output rectified images.
125 ### Step 6: At runtime, fill the Gaussian pyramids with the rectified frames
126 At runtime, fill the left and right Gaussian pyramids with the rectified frames as follows:
129 dwImageFilter_computePyramid(&leftPyramid, &outputRectifiedLeft, 0, context);
130 dwImageFilter_computePyramid(&rightPyramid, &outputRectifiedRight, 0, context);
133 where `leftPyramid` and `rightPyramid` are `::dwPyramidImage` objects that have already been initialized.
135 @note The Stereo algorithm works with greyscale images only. Therefore, `outputRectifiedLeft` and `outputRectifiedRight` must have only one plane.
136 Otherwise, additional steps may be required before building the pyramids.
137 For example, in the case of RGBA images, you would have first to convert to YUV and then extract the Y-plane (by calling `dwImageCUDA_getPlaneAsImage()`) before building the pyramids.
139 ### Step 7: Compute the disparity map
140 Call `dwStereo_computeDisparity()` to compute the disparity map based on the parameters set in `dwStereoParams`.
143 // Compute disparity given left and right pyramid
144 dwStereo_computeDisparity(leftPyramid, rightPyramid, stereoAlgorithm));
147 `dwStereo_getDisparity()` can be called to retrieve the disparity map of the desired side.
150 // get disparity maps
151 const dwImageCUDA *disparityLeft, *disparityRight;
152 dwStereo_getDisparity(disparityLeft, DW_STEREO_SIDE_LEFT, stereoAlgorithm);
153 dwStereo_getDisparity(disparityRight, DW_STEREO_SIDE_RIGHT, stereoAlgorithm));
156 ### Step 8 (Optional): Get an estimation of the confidence associated with each map
157 In cases where further processing is performed, it can be useful to have an estimation of the confidence associated to each disparity map.
159 To retrieve the confidence map of the corresponding disparity map, call `dwStereo_getConfidence()` as follows:
162 // get confidence maps
163 const dwImageCUDA *confidenceLeft, *confidenceRight;
164 dwStereo_getConfidence(confidenceLeft, DW_STEREO_SIDE_LEFT, stereoAlgorithm);
165 dwStereo_getConfidence(confidenceRight, DW_STEREO_SIDE_RIGHT, stereoAlgorithm);
168 Confidence is defined as an 8-bit value, where:
169 - 0 represents occlusion
170 - 1 represents an invalid disparity
171 - Other values represent a confidence score where 255 is maximum and 2 is minimum
173 An occlusion is a region of the image that is visible in one stereo image but not in the other.
174 An invalid disparity is found in regions containing no information, and its value has no confidence.
176 To obtain a real occlusion in the confidence map, both disparity maps must be computed. If only one is computed, then the occlusion can be roughly found among low confidence pixels in the confidence map.
178 Extracting a disparity map with a resolution lower than that of the input images can greatly improve the runtime and smoothness of the result. However, this improvement comes at the expense of edge precision and overall estimation accuracy.
180 ### Step 9: Release the stereo rectifier and stereo algorithm
181 Finally, release the stereo rectifier and stereo algorithm as follows:
184 // Release stereo rectifier
185 dwStereoRectifier_release(stereoRectifier);
187 // Release stereo module
188 dwStereo_release(stereoAlgorithm);
191 For more details see @ref dwx_stereo_disparity_sample, where it is shown how to perform image rectification and disparity estimation on a video pair. In the sample, horizontal lines are rendered to show how the pixels in both rectified images lay on the same horizontal line and the resulting disparity maps are visualized.