- Welcome
- Getting Started With the NVIDIA DriveWorks SDK
- Modules
- Samples
- Tools
- Tutorials
- SDK Porting Guide
- DriveWorks API
- More
This section explains how to use NVIDIA® DriveWorks Stereo Rectifier and Stereo to rectify two images of a stereo pair and compute a disparity map from them. 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.
Before you can initialize the stereo rectifier, you must first obtain the intrinsic and extrinsic camera parameters for the left and right camera.
The camera intrinsics encompass data such as focal length and principal point. The intrinsic parameters of each camera are represented by a dwCameraModelHandle_t
object. They can be obtained from the rig configuration as follows:
where rigConfigurationHandle
is a previously initialized dwRigHandle_t
; for more information on rig configuration see Rig Configuration. leftCamera_ID
and rightCamera_ID
are the corresponding known camera IDs in the rig file.
The camera extrinsics encompass the misalignment of the camera with respect to the rig in terms of rotation and translation. The extrinsic parameters of each camera are represented by a dwTransformation
object. They can be obtained from the rig configuration as follows:
Once intrinsic and extrinsic parameters of both cameras are available, you can initialize the stereo rectifier handle dwStereoRectifierHandle_t
as follows:
where contextHandle
is a previously initialized dwContextHandle_t
.
To initialize a dwStereoHandle_t
object, only dwStereoParams
is required. For example, the following example initializes stereo parameters with default values:
And the following modifies the parameters according to application requirements:
For more information regarding all available parameters, please refer to the dwStereoParams
struct.
dwStereoParams
parameters might be of special interest for the user: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.maxDisparityRange
: Smaller values can speed up the algorithm.refinementLevel
: A high refinement level will lead to a smoother disparity map.initType
: In general, it is advisable to always try several cost types, as their performance is dependent on the image content.After initializing the stereo parameters, initialize the module as follows:
where contextHandle
is assumed to be a previously initialized dwContextHandle_t
.
The rectification process applies a geometric transformation that projects the two images onto a common image plane. This plane contains a rectangular region that is shared by both images after rectification, graphically represented by the magenta boxes in the module diagram. It is represented by a dwBox2D
object, which can be retrieved as follows:
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:
where imageProperties
are known input image properties. Furthermore, you could use roi
when creating image streamers for visualization purposes.
Execute the rectification process by calling dwStereoRectifier_rectify()
. In the following snippet, stereoImageLeft
and stereoImageRight
must have been obtained from two input videos or a single stereo camera.
where outputRectifiedLeft
and outputRectifiedRight
now contain the output rectified images.
At runtime, fill the left and right Gaussian pyramids with the rectified frames as follows:
where leftPyramid
and rightPyramid
are dwPyramidImage
objects that have already been initialized.
outputRectifiedLeft
and outputRectifiedRight
must have only one plane. Otherwise, additional steps may be required before building the pyramids. 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.Call dwStereo_computeDisparity()
to compute the disparity map based on the parameters set in dwStereoParams
.
dwStereo_getDisparity()
can be called to retrieve the disparity map of the desired side.
In cases where further processing is performed, it can be useful to have an estimation of the confidence associated to each disparity map.
To retrieve the confidence map of the corresponding disparity map, call dwStereo_getConfidence()
as follows:
Confidence is defined as an 8-bit value, where:
An occlusion is a region of the image that is visible in one stereo image but not in the other. An invalid disparity is found in regions containing no information, and its value has no confidence.
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.
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.
Finally, release the stereo rectifier and stereo algorithm as follows:
For more details see 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.