DriveWorks SDK Reference
3.5.78 Release
For Test and Development only

Disparity Computation Workflow on PVA and NVENC
Note
SW Release Applicability: This tutorial is applicable to modules in both NVIDIA DriveWorks and NVIDIA DRIVE Software releases.

This section explains how to use NVIDIA® DriveWorks Stereo PVA module to compute a disparity map from two rectified dwImageHandle_t images.

For more information about rectifying images, see Disparity Computation Workflow.

Step 1: Initialize the stereo pva handle

To initialize a dwStereoPVAHandle_t object, dwStereoPVAParams is required. To illustrate, the following example initializes stereo parameters with default values:

dwStereoPVAParams stereoParams{};
dwStereoPVA_initParams(&stereoParams);

And the following modifies the parameters according to application requirements:

// Set estimation mode to high quality.
stereoParams.estimationMode = DW_STEREO_PVA_MODE_HIGH_QUALITY;
// The PVA parts of the pipeline will run on PVA 0.
stereoParams.processorPVA = DW_PROCESSOR_PVA_0;
// The NVENC parts of the pipeline will run on NVENC 0.
stereoParams.processorNVENC = DW_PROCESSOR_NVENC_0;

For mor information regarding all available parameters, please refer to the dwStereoPVAParams structure.

Note
Estimation mode affects both the computational performance and the quality of the algorithm. This should be adjusted according to the requirements of the application.

After initializing the stereo parameters, initialize the module as follows:

// initialize stereo module
dwStereoPVAHandle_t stereoAlgorithm;
dwStereoPVA_initialize(stereoAlgorithm, imageWidth, imageHeight, &stereoParams, contextHandle);

where contextHandle is assumed to be a previously initialized dwContextHandle_t.

Step 2: Inputs and outputs

StereoPVA module expects either NvMedia or CUDA image of DW_IMAGE_FORMAT_YUV420_UINT8_SEMIPLANAR format as rectified input images.

StereoPVA module provides functions to determine the size, type and format of the outputs in order to be able to create them on the application side.

The properties of the outputs can be obtained by:

// Get image properties for disparity output
dwImageProperties disparityImageProperties{};
dwImageProperties confidenceImageProperties{};
dwStereoPVA_getDisparityImageProperties(&disparityImageProperties, stereoAlgorithm);
dwStereoPVA_getConfidenceImageProeprties(&confidenceImageProperties, stereoAlgorithm);

The images can be constructed with the properties:

dwImage_create(&disparityOutput, disparityImageProperties, contextHandle);
dwImage_create(&confidenceOutput, disparityImageProperties, contextHandle);

Step 3: Compute the disparity map

Call dwStereoPVA_computeDisparity() to compute the disparity map and the confidence map based on the parameters set in dwStereoPVAParams. The disparity is computed from left to right.

// Compute disparity given left and right pyramid
dwStereoPVA_computeDisparity(disparityMap, confidenceMap, leftRectifiedImage, rightRectifiedImage, stereoAlgorithm));

Disparity is defined as an 8-bit unsigned value. Confidence is defines as a 16-bit unsigned value representing how reliable the associated disparity value is.

The disparity computation pipeline consists of multiple stages and utilizes multiple hardware engines, namely CPU, VIC (Video Image Compositor), PVA (Programmable Vision Accelerator), NVENC (Video Encoder) and GPU.

Step 4: Release the stereo algorithm

Finally, release the stereo rectifier and stereo algorithm as follows:

// Release stereo module
dwStereoPVA_release(stereoAlgorithm);

For more details see Stereo Disparity PVA Sample, where it is shown how to perform image rectification and disparity estimation on multiple hardware accelerators on a video pair.