- Welcome
- Getting Started With the NVIDIA DriveWorks SDK
- Modules
- Samples
- Tools
- Tutorials
- SDK Porting Guide
- DriveWorks API
- More
Runs the stereo pipeline and computes disparity map.
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... | |
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). |
typedef struct dwStereoObject* dwStereoHandle_t |
typedef struct dwStereoRectifierObject* dwStereoRectifierHandle_t |
enum dwStereoCostType |
enum dwStereoSide |
DW_API_PUBLIC dwStatus dwStereo_computeDisparity | ( | const dwPyramidImage * | leftPyramid, |
const dwPyramidImage * | rightPyramid, | ||
dwStereoHandle_t | obj | ||
) |
Computes the disparity map given the two rectified views.
[in] | leftPyramid | The left 8 bit rectified image pyramid. |
[in] | rightPyramid | The left 8 bit rectified image pyramid. |
[in] | obj | The stereo algorithm handle. |
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
[out] | confidenceMap | A 2D matrix containing confidence values in 8 bit. |
[in] | side | The side, either DW_STEREO_SIDE_LEFT or DW_STEREO_SIDE_RIGHT |
[in] | obj | The stereo algorithm handle. |
DW_API_PUBLIC dwStatus dwStereo_getCUDAStream | ( | cudaStream_t * | stream, |
dwStereoHandle_t | obj | ||
) |
Gets CUDA stream used by the stereo algorithm.
[out] | stream | The CUDA stream currently used by the stereo algorithm. |
[in] | obj | The stereo algorithm handle. |
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
[out] | disparityMap | A 2D matrix containing disparity values in 8 bit. |
[in] | side | The side, either DW_STEREO_SIDE_LEFT or DW_STEREO_SIDE_RIGHT |
[in] | obj | The stereo algorithm handle. |
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.
[out] | dispWidth | with of the image. |
[out] | dispHeight | height of the image. |
[in] | gLevel | level of the pyramid. |
[in] | obj | The stereo algorithm handle. |
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.
[out] | obj | A pointer to the stereo algorithm. |
[in] | width | The width of one input image. |
[in] | height | The height of one input image. |
[in] | stereoParams | A pointer to the configuration of the stereo algorithm. |
[in] | ctx | the handle to DW context. |
DW_API_PUBLIC dwStatus dwStereo_initParams | ( | dwStereoParams * | stereoParams | ) |
Initializes the stereo parameters.
[out] | stereoParams | Parameters to be initialised with default values. |
DW_API_PUBLIC dwStatus dwStereo_release | ( | dwStereoHandle_t | obj | ) |
Releases the stereo algorithm.
This method releases all resources associated with a stereo algorithm.
[in] | obj | The object handle to be released. |
DW_API_PUBLIC dwStatus dwStereo_reset | ( | dwStereoHandle_t | obj | ) |
Resets the Stereo module.
[in] | obj | Specifies the stereo handle to reset. |
DW_API_PUBLIC dwStatus dwStereo_setCUDAStream | ( | cudaStream_t | stream, |
dwStereoHandle_t | obj | ||
) |
Sets CUDA stream used by the stereo algorithm.
[in] | stream | The CUDA stream. |
[in] | obj | The stereo algorithm handle. |
DW_API_PUBLIC dwStatus dwStereo_setInfill | ( | bool | doInfill, |
dwStereoHandle_t | obj | ||
) |
Set invalid infill on/off.
[in] | doInfill | a bool to activate test. |
[in] | obj | The stereo algorithm handle. |
DW_API_PUBLIC dwStatus dwStereo_setInvalidThreshold | ( | float32_t | threshold, |
dwStereoHandle_t | obj | ||
) |
Set invalidity threshold.
[in] | threshold | a float value for invalidity |
[in] | obj | The stereo algorithm handle. |
DW_API_PUBLIC dwStatus dwStereo_setOcclusionInfill | ( | bool | doInfill, |
dwStereoHandle_t | obj | ||
) |
Set occlusion infill on/off.
[in] | doInfill | a bool to activate test. |
[in] | obj | The stereo algorithm handle. |
DW_API_PUBLIC dwStatus dwStereo_setOcclusionTest | ( | bool | doTest, |
dwStereoHandle_t | obj | ||
) |
Set occlusion test on/off.
[in] | doTest | a bool to activate test. |
[in] | obj | The stereo algorithm handle. |
DW_API_PUBLIC dwStatus dwStereo_setRefinementLevel | ( | uint8_t | refinementLvl, |
dwStereoHandle_t | obj | ||
) |
Sets the refinement level of the ongoing stereo algorithm.
[in] | refinementLvl | the refinement level between 0 and 6. |
[in] | obj | The stereo algorithm handle. |
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
[out] | roi | Pointer to a 2D box defining the roi to crop. |
[in] | obj | A pointer to the rectifier handle. |
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.
[out] | projectionMat | Pointer to a dwMatrix3x4f. |
[in] | side | The stereo side |
[in] | obj | A pointer to the rectifier handle. |
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
[out] | rRectMat | Pointer to a dwMatrix3f. |
[in] | side | The stereo side |
[in] | obj | A pointer to the rectifier handle. |
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.
[out] | qMatrix | Pointer to a dwMatrix4f. |
[in] | obj | A pointer to the rectifier handle. |
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.
[out] | obj | A pointer to the stereo rectifier. |
[in] | cameraLeft | a handle to the calibrated camera of the left eye. |
[in] | cameraRight | a handle to the calibrated camera of the right eye. |
[in] | leftToRig | the extrinsic matrix from letf camera to rig centre (usually the left camera itself). |
[in] | rightToRig | the extrinsic matrix from right camera to rig centre. |
[in] | ctx | A handle to DW context. |
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.
[out] | outputImageLeft | Pointer to the output left image. |
[out] | outputImageRight | Pointer to the output right image. |
[in] | inputImageLeft | Pointer to the left input image. |
[in] | inputImageRight | Pointer to the right input image. |
[in] | obj | A pointer to the rectifier handle. |
DW_API_PUBLIC dwStatus dwStereoRectifier_release | ( | dwStereoRectifierHandle_t | obj | ) |
Releases the stereo rectifier.
[in] | obj | The stereo algorithm. |