DriveWorks SDK Reference
3.5.78 Release
For Test and Development only

Stereo Interface

Detailed Description

Runs the stereo pipeline and computes disparity map.

Note
SW Release Applicability: These APIs are available in both NVIDIA DriveWorks and NVIDIA DRIVE Software releases.

Data Structures

struct  dwStereoParams
 Configuration parameters for a Stereo algorithm. More...
 

Macros

#define DW_STEREO_SIDE_COUNT   2
 
#define MAX_ALLOWED_DISPARITY_RANGE   1024
 

Typedefs

typedef struct dwStereoObject * dwStereoHandle_t
 A pointer to the handle representing a stereo algorithm. More...
 
typedef struct dwStereoRectifierObject * dwStereoRectifierHandle_t
 A pointer to the handle representing a stereo rectifier. More...
 

Enumerations

enum  dwStereoCostType {
  DW_STEREO_COST_AD,
  DW_STEREO_COST_NCC,
  DW_STEREO_COST_SAD,
  DW_STEREO_COST_CENSUS,
  DW_STEREO_COST_ADCENSUS
}
 Cost types for matching. More...
 
enum  dwStereoRectifierCrop {
  DW_STEREO_RECTIFIER_UNCHANGED,
  DW_STEREO_RECTIFIER_CROP
}
 Cropping. More...
 
enum  dwStereoSide {
  DW_STEREO_SIDE_LEFT = 0,
  DW_STEREO_SIDE_RIGHT,
  DW_STEREO_SIDE_BOTH
}
 Side. More...
 

Functions

DW_API_PUBLIC dwStatus dwStereo_computeDisparity (const dwPyramidImage *leftPyramid, const dwPyramidImage *rightPyramid, dwStereoHandle_t obj)
 Computes the disparity map given the two rectified views. More...
 
DW_API_PUBLIC dwStatus dwStereo_getConfidence (const dwImageCUDA **confidenceMap, dwStereoSide side, dwStereoHandle_t obj)
 Returns the confidence map for a specified side. More...
 
DW_API_PUBLIC dwStatus dwStereo_getCUDAStream (cudaStream_t *stream, dwStereoHandle_t obj)
 Gets CUDA stream used by the stereo algorithm. More...
 
DW_API_PUBLIC dwStatus dwStereo_getDisparity (const dwImageCUDA **disparityMap, dwStereoSide side, dwStereoHandle_t obj)
 Returns the disparity map for a specified side. More...
 
DW_API_PUBLIC dwStatus dwStereo_getSize (uint32_t *dispWidth, uint32_t *dispHeight, uint32_t gLevel, dwStereoHandle_t obj)
 Get size of image at a certain level. More...
 
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. More...
 
DW_API_PUBLIC dwStatus dwStereo_initParams (dwStereoParams *stereoParams)
 Initializes the stereo parameters. More...
 
DW_API_PUBLIC dwStatus dwStereo_release (dwStereoHandle_t obj)
 Releases the stereo algorithm. More...
 
DW_API_PUBLIC dwStatus dwStereo_reset (dwStereoHandle_t obj)
 Resets the Stereo module. More...
 
DW_API_PUBLIC dwStatus dwStereo_setCUDAStream (cudaStream_t stream, dwStereoHandle_t obj)
 Sets CUDA stream used by the stereo algorithm. More...
 
DW_API_PUBLIC dwStatus dwStereo_setInfill (bool doInfill, dwStereoHandle_t obj)
 Set invalid infill on/off. More...
 
DW_API_PUBLIC dwStatus dwStereo_setInvalidThreshold (float32_t threshold, dwStereoHandle_t obj)
 Set invalidity threshold. More...
 
DW_API_PUBLIC dwStatus dwStereo_setOcclusionInfill (bool doInfill, dwStereoHandle_t obj)
 Set occlusion infill on/off. More...
 
DW_API_PUBLIC dwStatus dwStereo_setOcclusionTest (bool doTest, dwStereoHandle_t obj)
 Set occlusion test on/off. More...
 
DW_API_PUBLIC dwStatus dwStereo_setRefinementLevel (uint8_t refinementLvl, dwStereoHandle_t obj)
 Sets the refinement level of the ongoing stereo algorithm. More...
 
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. More...
 
DW_API_PUBLIC dwStatus dwStereoRectifier_getProjectionMatrix (dwMatrix34f *projectionMat, dwStereoSide side, dwStereoRectifierHandle_t obj)
 Returns a 3x4 projection matrix for the side specified of the form: P_left = M_rect_left*[I|0] P_right = M_rict_right*[I|Tx] with M the rectified intrinsics matrix and Tx the baseline. More...
 
DW_API_PUBLIC dwStatus dwStereoRectifier_getRectificationMatrix (dwMatrix3f *rRectMat, dwStereoSide side, dwStereoRectifierHandle_t obj)
 Returns a 3x3 rotation matrix for the side specified. More...
 
DW_API_PUBLIC dwStatus dwStereoRectifier_getReprojectionMatrix (dwMatrix4f *qMatrix, dwStereoRectifierHandle_t obj)
 Returns a 4x4 reprojetion matrix of the form 1, 0, 0, -Cx Q = 0, 1, 0, -Cy 0, 0, 0, foc 0, 0,-1/Tx, (Cx - C'x)/Tx. More...
 
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. More...
 
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. More...
 
DW_API_PUBLIC dwStatus dwStereoRectifier_release (dwStereoRectifierHandle_t obj)
 Releases the stereo rectifier. More...
 

Data Structure Documentation

◆ dwStereoParams

struct dwStereoParams
Data Fields
uint32_t height Input image height.
bool holesFilling Specifies whether to fill invalid pixel using assumption on the scene in order to have a map with 100% density.
dwStereoCostType initType Specifies the cost type used for initialization.
float32_t invalidityThreshold Specifies threshold of invalidity.
uint32_t levelCount Number of levels in the pyramid. It must be the same or less than that of the Gaussian pyramid.
uint32_t levelStop Level of the pyramid where disparity computation ends. It defines the resolution of the output disparity and confidence maps.
uint32_t maxDisparityRange Maximal displacement when searching for corresponding pixels.
bool occlusionFilling Specifies whether to fill occluded pixels for 100% density.
bool occlusionTest Specifies whether to perform a L/R occlusion test.
uint32_t occlusionThreshold Threshold for failing the L/R consistency test (in disparity value).
uint8_t refinementLevel Refinement level (0 no refinement, 1-3)
dwStereoSide side Side to compute the disparity map of.
uint32_t width Input image width (single image).

Macro Definition Documentation

◆ DW_STEREO_SIDE_COUNT

#define DW_STEREO_SIDE_COUNT   2

Definition at line 69 of file Stereo.h.

◆ MAX_ALLOWED_DISPARITY_RANGE

#define MAX_ALLOWED_DISPARITY_RANGE   1024

Definition at line 70 of file Stereo.h.

Typedef Documentation

◆ dwStereoHandle_t

typedef struct dwStereoObject* dwStereoHandle_t

A pointer to the handle representing a stereo algorithm.

This object allows the computation of a disparity map given two rectified stereo images

Definition at line 67 of file Stereo.h.

◆ dwStereoRectifierHandle_t

typedef struct dwStereoRectifierObject* dwStereoRectifierHandle_t

A pointer to the handle representing a stereo rectifier.

This object allows the rectification of two stereo images based on calibration matrices

Definition at line 349 of file Stereo.h.

Enumeration Type Documentation

◆ dwStereoCostType

Cost types for matching.

Enumerator
DW_STEREO_COST_AD 

Absolute difference.

DW_STEREO_COST_NCC 

Normalised cross correlation.

DW_STEREO_COST_SAD 

Sum of absolute differences.

DW_STEREO_COST_CENSUS 

Census transform.

DW_STEREO_COST_ADCENSUS 

Absolute difference and census.

Definition at line 87 of file Stereo.h.

◆ dwStereoRectifierCrop

Cropping.

Enumerator
DW_STEREO_RECTIFIER_UNCHANGED 

No scaling, keeps output of rectifier.

DW_STEREO_RECTIFIER_CROP 

Crops to inner valid rectangle.

Definition at line 354 of file Stereo.h.

◆ dwStereoSide

Side.

Enumerator
DW_STEREO_SIDE_LEFT 

Left.

DW_STEREO_SIDE_RIGHT 

Right.

DW_STEREO_SIDE_BOTH 

Both sides.

Definition at line 75 of file Stereo.h.

Function Documentation

◆ dwStereo_computeDisparity()

DW_API_PUBLIC dwStatus dwStereo_computeDisparity ( const dwPyramidImage leftPyramid,
const dwPyramidImage rightPyramid,
dwStereoHandle_t  obj 
)

Computes the disparity map given the two rectified views.

Parameters
[in]leftPyramidThe left 8 bit rectified image pyramid.
[in]rightPyramidThe left 8 bit rectified image pyramid.
[in]objThe stereo algorithm handle.
Returns
DW_CUDA_ERROR - if the underlying stereo algorithm had a CUDA error.
DW_INVALID_HANDLE - if given handle is not valid, i.e. null or of wrong type .
DW_SUCCESS

◆ dwStereo_getConfidence()

DW_API_PUBLIC dwStatus dwStereo_getConfidence ( const dwImageCUDA **  confidenceMap,
dwStereoSide  side,
dwStereoHandle_t  obj 
)

Returns the confidence map for a specified side.

Requires dwStereo_computeDisparity() to be done first

Parameters
[out]confidenceMapA 2D matrix containing confidence values in 8 bit.
[in]sideThe side, either DW_STEREO_SIDE_LEFT or DW_STEREO_SIDE_RIGHT
[in]objThe stereo algorithm handle.
Returns
DW_CUDA_ERROR - if the underlying stereo algorithm had a CUDA error.
DW_INVALID_HANDLE - if given handle is not valid, i.e. null or of wrong type .
DW_INVALID_ARGUMENT - if the input images have a mismatching attribute
DW_SUCCESS

◆ dwStereo_getCUDAStream()

DW_API_PUBLIC dwStatus dwStereo_getCUDAStream ( cudaStream_t *  stream,
dwStereoHandle_t  obj 
)

Gets CUDA stream used by the stereo algorithm.

Parameters
[out]streamThe CUDA stream currently used by the stereo algorithm.
[in]objThe stereo algorithm handle.
Returns
DW_INVALID_HANDLE if the given context handle is invalid, i.e. null or of wrong type
or DW_SUCCESS otherwise.

◆ dwStereo_getDisparity()

DW_API_PUBLIC dwStatus dwStereo_getDisparity ( const dwImageCUDA **  disparityMap,
dwStereoSide  side,
dwStereoHandle_t  obj 
)

Returns the disparity map for a specified side.

Requires dwStereo_computeDisparity() to be done first

Parameters
[out]disparityMapA 2D matrix containing disparity values in 16 bit.
[in]sideThe side, either DW_STEREO_SIDE_LEFT or DW_STEREO_SIDE_RIGHT
[in]objThe stereo algorithm handle.
Returns
DW_CUDA_ERROR - if the underlying stereo algorithm had a CUDA error.
DW_INVALID_HANDLE - if given handle is not valid, i.e. null or of wrong type .
DW_INVALID_ARGUMENT - if the input images have a mismatching attribute
DW_SUCCESS

◆ dwStereo_getSize()

DW_API_PUBLIC dwStatus dwStereo_getSize ( uint32_t *  dispWidth,
uint32_t *  dispHeight,
uint32_t  gLevel,
dwStereoHandle_t  obj 
)

Get size of image at a certain level.

Parameters
[out]dispWidthwith of the image.
[out]dispHeightheight of the image.
[in]gLevellevel of the pyramid.
[in]objThe stereo algorithm handle.
Returns
DW_SUCCESS

◆ dwStereo_initialize()

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.

Parameters
[out]objA pointer to the stereo algorithm.
[in]widthThe width of one input image.
[in]heightThe height of one input image.
[in]stereoParamsA pointer to the configuration of the stereo algorithm.
[in]ctxthe handle to DW context.
Returns
DW_CUDA_ERROR - if the underlying stereo algorithm had a CUDA error.
DW_INVALID_HANDLE - if given handle is not valid, i.e. null or of wrong type .
DW_SUCCESS

◆ dwStereo_initParams()

DW_API_PUBLIC dwStatus dwStereo_initParams ( dwStereoParams stereoParams)

Initializes the stereo parameters.

Parameters
[out]stereoParamsParameters to be initialised with default values.
Returns
DW_INVALID_HANDLE - if given handle is not valid, i.e. null or of wrong type .
DW_SUCCESS

◆ dwStereo_release()

DW_API_PUBLIC dwStatus dwStereo_release ( dwStereoHandle_t  obj)

Releases the stereo algorithm.

This method releases all resources associated with a stereo algorithm.

Note
This method renders the handle unusable.
Parameters
[in]objThe object handle to be released.
Returns
DW_SUCCESS
DW_INVALID_HANDLE - If the given context handle is invalid,i.e. null or of wrong type
DW_BAD_CAST

◆ dwStereo_reset()

DW_API_PUBLIC dwStatus dwStereo_reset ( dwStereoHandle_t  obj)

Resets the Stereo module.

Parameters
[in]objSpecifies the stereo handle to reset.
Returns
DW_SUCCESS
DW_INVALID_HANDLE - If the given context handle is invalid,i.e. null or of wrong type
DW_BAD_CAST

◆ dwStereo_setCUDAStream()

DW_API_PUBLIC dwStatus dwStereo_setCUDAStream ( cudaStream_t  stream,
dwStereoHandle_t  obj 
)

Sets CUDA stream used by the stereo algorithm.

Parameters
[in]streamThe CUDA stream.
[in]objThe stereo algorithm handle.
Returns
DW_INVALID_HANDLE if the given context handle is invalid,i.e. null or of wrong type
or DW_SUCCESS otherwise.

◆ dwStereo_setInfill()

DW_API_PUBLIC dwStatus dwStereo_setInfill ( bool  doInfill,
dwStereoHandle_t  obj 
)

Set invalid infill on/off.

Parameters
[in]doInfilla bool to activate test.
[in]objThe stereo algorithm handle.
Returns
DW_SUCCESS

◆ dwStereo_setInvalidThreshold()

DW_API_PUBLIC dwStatus dwStereo_setInvalidThreshold ( float32_t  threshold,
dwStereoHandle_t  obj 
)

Set invalidity threshold.

Parameters
[in]thresholda float value for invalidity
[in]objThe stereo algorithm handle.
Returns
DW_SUCCESS

◆ dwStereo_setOcclusionInfill()

DW_API_PUBLIC dwStatus dwStereo_setOcclusionInfill ( bool  doInfill,
dwStereoHandle_t  obj 
)

Set occlusion infill on/off.

Parameters
[in]doInfilla bool to activate test.
[in]objThe stereo algorithm handle.
Returns
DW_SUCCESS

◆ dwStereo_setOcclusionTest()

DW_API_PUBLIC dwStatus dwStereo_setOcclusionTest ( bool  doTest,
dwStereoHandle_t  obj 
)

Set occlusion test on/off.

Parameters
[in]doTesta bool to activate test.
[in]objThe stereo algorithm handle.
Returns
DW_SUCCESS

◆ dwStereo_setRefinementLevel()

DW_API_PUBLIC dwStatus dwStereo_setRefinementLevel ( uint8_t  refinementLvl,
dwStereoHandle_t  obj 
)

Sets the refinement level of the ongoing stereo algorithm.

Parameters
[in]refinementLvlthe refinement level between 0 and 6.
[in]objThe stereo algorithm handle.
Returns
DW_CUDA_ERROR - if the underlying stereo algorithm had a CUDA error.
DW_INVALID_HANDLE - if given handle is not valid, i.e. null or of wrong type .
DW_INVALID_ARGUMENT - if the input images have a mismatching attribute
DW_SUCCESS

◆ dwStereoRectifier_getCropROI()

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.

It is used for cropping

Parameters
[out]roiPointer to a 2D box defining the roi to crop.
[in]objA pointer to the rectifier handle.
Returns
DW_INVALID_HANDLE - if given handle is not valid, i.e. null or of wrong type .
DW_SUCCESS

◆ dwStereoRectifier_getProjectionMatrix()

DW_API_PUBLIC dwStatus dwStereoRectifier_getProjectionMatrix ( dwMatrix34f projectionMat,
dwStereoSide  side,
dwStereoRectifierHandle_t  obj 
)

Returns a 3x4 projection matrix for the side specified of the form: P_left = M_rect_left*[I|0] P_right = M_rict_right*[I|Tx] with M the rectified intrinsics matrix and Tx the baseline.

Parameters
[out]projectionMatPointer to a dwMatrix3x4f.
[in]sideThe stereo side
[in]objA pointer to the rectifier handle.
Returns
DW_INVALID_HANDLE - if given handle is not valid, i.e. null or of wrong type .
DW_SUCCESS

◆ dwStereoRectifier_getRectificationMatrix()

DW_API_PUBLIC dwStatus dwStereoRectifier_getRectificationMatrix ( dwMatrix3f rRectMat,
dwStereoSide  side,
dwStereoRectifierHandle_t  obj 
)

Returns a 3x3 rotation matrix for the side specified.

The matrix sends epipoles to infinity

Parameters
[out]rRectMatPointer to a dwMatrix3f.
[in]sideThe stereo side
[in]objA pointer to the rectifier handle.
Returns
DW_INVALID_HANDLE - if given handle is not valid, i.e. null or of wrong type .
DW_SUCCESS

◆ dwStereoRectifier_getReprojectionMatrix()

DW_API_PUBLIC dwStatus dwStereoRectifier_getReprojectionMatrix ( dwMatrix4f qMatrix,
dwStereoRectifierHandle_t  obj 
)

Returns a 4x4 reprojetion matrix of the form 1, 0, 0, -Cx Q = 0, 1, 0, -Cy 0, 0, 0, foc 0, 0,-1/Tx, (Cx - C'x)/Tx.

Parameters
[out]qMatrixPointer to a dwMatrix4f.
[in]objA pointer to the rectifier handle.
Returns
DW_INVALID_HANDLE - if given handle is not valid, i.e. null or of wrong type .
DW_SUCCESS

◆ dwStereoRectifier_initialize()

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.

Parameters
[out]objA pointer to the stereo rectifier.
[in]cameraLefta handle to the calibrated camera of the left eye.
[in]cameraRighta handle to the calibrated camera of the right eye.
[in]leftToRigthe extrinsic matrix from letf camera to rig centre (usually the left camera itself).
[in]rightToRigthe extrinsic matrix from right camera to rig centre.
[in]ctxA handle to DW context.
Returns
DW_CUDA_ERROR - if the underlying rectifier had a CUDA error during initialization.
DW_INVALID_HANDLE - if given handle is not valid, i.e. null or of wrong type .
DW_SUCCESS

◆ dwStereoRectifier_rectify()

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.

Parameters
[out]outputImageLeftPointer to the output left image.
[out]outputImageRightPointer to the output right image.
[in]inputImageLeftPointer to the left input image.
[in]inputImageRightPointer to the right input image.
[in]objA pointer to the rectifier handle.
Returns
DW_CUDA_ERROR - if the underlying stereo algorithm had a CUDA error.
DW_INVALID_HANDLE - if given handle is not valid, i.e. null or of wrong type .
DW_SUCCESS

◆ dwStereoRectifier_release()

DW_API_PUBLIC dwStatus dwStereoRectifier_release ( dwStereoRectifierHandle_t  obj)

Releases the stereo rectifier.

Parameters
[in]objThe stereo algorithm.
Returns
DW_INVALID_HANDLE - if given handle is not valid, i.e. null or of wrong type .
DW_SUCCESS