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.
Step 1: Obtain the intrinsic and extrinsic camera parameters for the left and right camera
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:
struct dwCameraModelObject * dwCameraModelHandle_t
A pointer to the handle representing a calibrated camera model.
DW_API_PUBLIC dwStatus dwCameraModel_initialize(dwCameraModelHandle_t *camera, uint32_t sensorId, dwConstRigHandle_t obj)
Creates a calibrated camera model polymorphically for a compatible sensor.
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:
DW_API_PUBLIC dwStatus dwRig_getSensorToRigTransformation(dwTransformation3f *const transformation, uint32_t const sensorId, dwConstRigHandle_t const obj)
Gets the sensor to rig transformation for a sensor.
Step 2: Initialize the stereo rectifier and the stereo handle
Once intrinsic and extrinsic parameters of both cameras are available, you can initialize the stereo rectifier handle dwStereoRectifierHandle_t
as follows:
struct dwStereoRectifierObject * dwStereoRectifierHandle_t
A pointer to the handle representing a stereo rectifier.
DW_API_PUBLIC dwStatus dwStereoRectifier_initialize(dwStereoRectifierHandle_t *obj, dwCameraModelHandle_t cameraLeft, dwCameraModelHandle_t cameraRight, dwTransformation3f leftToRig, dwTransformation3f rightToRig, dwContextHandle_t ctx)
Initializes the stereo rectifier.
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:
DW_API_PUBLIC dwStatus dwStereo_initParams(dwStereoParams *stereoParams)
Initializes the stereo parameters.
Configuration parameters for a Stereo algorithm.
And the following modifies the parameters according to application requirements:
stereoParams.side = side;
stereoParams.levelCount = levelCount;
stereoParams.levelStop = levelStop;
For more information regarding all available parameters, please refer to the dwStereoParams
struct.
- Note
- The effects due to different settings of the following
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:
DW_API_PUBLIC dwStatus dwStereo_initialize(dwStereoHandle_t *obj, uint32_t width, uint32_t height, const dwStereoParams *stereoParams, dwContextHandle_t ctx)
Initializes the stereo algorithm with the parameters.
struct dwStereoObject * dwStereoHandle_t
A pointer to the handle representing a stereo algorithm.
where contextHandle
is assumed to be a previously initialized dwContextHandle_t
.
Step 3: Retrieve the rectangular ROI shared by both images
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:
DW_API_PUBLIC dwStatus dwStereoRectifier_getCropROI(dwBox2D *roi, dwStereoRectifierHandle_t obj)
Returns a rectangle which is the roi where all valid pixels after undistortion and rectification are.
Step 4: Create output images for the rectification process
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:
dwImageType type
Specifies the type of image.
uint32_t height
Specifies the height of the image in pixels.
uint32_t width
Specifies the width of the image in pixels.
dwImageFormat format
Specifies the format of the image.
struct dwImageObject * dwImageHandle_t
DW_API_PUBLIC dwStatus dwImage_create(dwImageHandle_t *const image, dwImageProperties properties, dwContextHandle_t const ctx)
Creates and allocates resources for a dwImageHandle_t based on the properties passed as input.
@ DW_IMAGE_FORMAT_RGBA_UINT8
Defines the properties of the image.
where imageProperties
are known input image properties. Furthermore, you could use roi
when creating image streamers for visualization purposes.
Step 5: At runtime, call the stereo rectification process
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.
DW_API_PUBLIC dwStatus dwStereoRectifier_rectify(dwImageCUDA *outputImageLeft, dwImageCUDA *outputImageRight, const dwImageCUDA *inputImageLeft, const dwImageCUDA *inputImageRight, dwStereoRectifierHandle_t obj)
Rectifies two images acquired by a stereo rig, epipolar lines will be parallel.
where outputRectifiedLeft
and outputRectifiedRight
now contain the output rectified images.
Step 6: At runtime, fill the Gaussian pyramids with the rectified frames
At runtime, fill the left and right Gaussian pyramids with the rectified frames as follows:
DW_API_PUBLIC dwStatus dwImageFilter_computePyramid(dwPyramidImage *pyramid, const dwImageCUDA *image, cudaStream_t stream, dwContextHandle_t context)
Builds the pyramid from level 0 image.
where leftPyramid
and rightPyramid
are dwPyramidImage
objects that have already been initialized.
- Note
- The Stereo algorithm works with greyscale images only. Pyramid will select plane automatically if
outputRectifiedLeft
and outputRectifiedRight
have more than one plane.
Step 7: Compute the disparity map
Call dwStereo_computeDisparity()
to compute the disparity map based on the parameters set in dwStereoParams
.
DW_API_PUBLIC dwStatus dwStereo_computeDisparity(const dwPyramidImage *leftPyramid, const dwPyramidImage *rightPyramid, dwStereoHandle_t obj)
Computes the disparity map given the two rectified views.
dwStereo_getDisparity()
can be called to retrieve the disparity map of the desired side.
DW_API_PUBLIC dwStatus dwStereo_getDisparity(const dwImageCUDA **disparityMap, dwStereoSide side, dwStereoHandle_t obj)
Returns the disparity map for a specified side.
@ DW_STEREO_SIDE_LEFT
Left.
@ DW_STEREO_SIDE_RIGHT
Right.
Step 8 (Optional): Get an estimation of the confidence associated with each map
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:
DW_API_PUBLIC dwStatus dwStereo_getConfidence(const dwImageCUDA **confidenceMap, dwStereoSide side, dwStereoHandle_t obj)
Returns the confidence map for a specified side.
Confidence is defined as an 8-bit value, where:
- 0 represents occlusion
- 1 represents an invalid disparity
- Other values represent a confidence score where 255 is maximum and 2 is minimum
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.
Step 9: Release the stereo rectifier and stereo algorithm
Finally, release the stereo rectifier and stereo algorithm as follows:
DW_API_PUBLIC dwStatus dwStereo_release(dwStereoHandle_t obj)
Releases the stereo algorithm.
DW_API_PUBLIC dwStatus dwStereoRectifier_release(dwStereoRectifierHandle_t obj)
Releases the stereo rectifier.
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.