DriveWorks SDK Reference
4.0.0 Release
For Test and Development only

Stereo.h
Go to the documentation of this file.
1 // This code contains NVIDIA Confidential Information and is disclosed
3 // under the Mutual Non-Disclosure Agreement.
4 //
5 // Notice
6 // ALL NVIDIA DESIGN SPECIFICATIONS AND CODE ("MATERIALS") ARE PROVIDED "AS IS" NVIDIA MAKES
7 // NO REPRESENTATIONS, WARRANTIES, EXPRESSED, IMPLIED, STATUTORY, OR OTHERWISE WITH RESPECT TO
8 // THE MATERIALS, AND EXPRESSLY DISCLAIMS ANY IMPLIED WARRANTIES OF NONINFRINGEMENT,
9 // MERCHANTABILITY, OR FITNESS FOR A PARTICULAR PURPOSE.
10 //
11 // NVIDIA Corporation assumes no responsibility for the consequences of use of such
12 // information or for any infringement of patents or other rights of third parties that may
13 // result from its use. No license is granted by implication or otherwise under any patent
14 // or patent rights of NVIDIA Corporation. No third party distribution is allowed unless
15 // expressly authorized by NVIDIA. Details are subject to change without notice.
16 // This code supersedes and replaces all information previously supplied.
17 // NVIDIA Corporation products are not authorized for use as critical
18 // components in life support devices or systems without express written approval of
19 // NVIDIA Corporation.
20 //
21 // Copyright (c) 2015-2019 NVIDIA Corporation. All rights reserved.
22 //
23 // NVIDIA Corporation and its licensors retain all intellectual property and proprietary
24 // rights in and to this software and related documentation and any modifications thereto.
25 // Any use, reproduction, disclosure or distribution of this software and related
26 // documentation without an express license agreement from NVIDIA Corporation is
27 // strictly prohibited.
28 //
30 
39 #ifndef DW_IMAGEPROCESSING_STEREO_STEREO_H_
40 #define DW_IMAGEPROCESSING_STEREO_STEREO_H_
41 
42 #include <dw/image/Image.h>
43 #include <dw/rig/Rig.h>
46 
47 #ifdef __cplusplus
48 extern "C" {
49 #endif
50 
59 // dwStereo
61 
65 typedef struct dwStereoObject* dwStereoHandle_t;
66 
67 #define DW_STEREO_SIDE_COUNT 2
68 #define MAX_ALLOWED_DISPARITY_RANGE 1024
69 
73 typedef enum {
80 } dwStereoSide;
81 
85 typedef enum {
97 
101 typedef struct
102 {
104  uint32_t width;
105 
107  uint32_t height;
108 
111 
113  uint32_t levelCount;
114 
116  uint32_t levelStop;
117 
119  dwStereoSide side;
120 
123 
126 
129 
132 
135 
138 
140  dwStereoCostType initType;
141 
143 
154 
169 dwStatus dwStereo_initialize(dwStereoHandle_t* obj, uint32_t width, uint32_t height,
170  const dwStereoParams* stereoParams, dwContextHandle_t ctx);
171 
185  const dwPyramidImage* rightPyramid, dwStereoHandle_t obj);
186 
200 dwStatus dwStereo_getDisparity(const dwImageCUDA** disparityMap, dwStereoSide side, dwStereoHandle_t obj);
201 
215 dwStatus dwStereo_getConfidence(const dwImageCUDA** confidenceMap, dwStereoSide side, dwStereoHandle_t obj);
216 
226 dwStatus dwStereo_setOcclusionTest(bool doTest, dwStereoHandle_t obj);
227 
237 dwStatus dwStereo_setOcclusionInfill(bool doInfill, dwStereoHandle_t obj);
238 
248 dwStatus dwStereo_setInfill(bool doInfill, dwStereoHandle_t obj);
249 
259 dwStatus dwStereo_setInvalidThreshold(float32_t threshold, dwStereoHandle_t obj);
260 
273 dwStatus dwStereo_setRefinementLevel(uint8_t refinementLvl, dwStereoHandle_t obj);
274 
286 dwStatus dwStereo_getSize(uint32_t* dispWidth, uint32_t* dispHeight, uint32_t gLevel,
287  dwStereoHandle_t obj);
288 
299 dwStatus dwStereo_setCUDAStream(cudaStream_t stream, dwStereoHandle_t obj);
300 
311 dwStatus dwStereo_getCUDAStream(cudaStream_t* stream, dwStereoHandle_t obj);
312 
323 dwStatus dwStereo_reset(dwStereoHandle_t obj);
324 
339 dwStatus dwStereo_release(dwStereoHandle_t obj);
340 
342 // dwStereoRectifier
343 
347 typedef struct dwStereoRectifierObject* dwStereoRectifierHandle_t;
348 
352 typedef enum {
358 
374 dwStatus dwStereoRectifier_initialize(dwStereoRectifierHandle_t* obj, dwCameraModelHandle_t cameraLeft,
375  dwCameraModelHandle_t cameraRight, dwTransformation3f leftToRig,
376  dwTransformation3f rightToRig, dwContextHandle_t ctx);
377 
387 dwStatus dwStereoRectifier_release(dwStereoRectifierHandle_t obj);
388 
403 dwStatus dwStereoRectifier_rectify(dwImageCUDA* outputImageLeft, dwImageCUDA* outputImageRight,
404  const dwImageCUDA* inputImageLeft, const dwImageCUDA* inputImageRight,
405  dwStereoRectifierHandle_t obj);
406 
418 dwStatus dwStereoRectifier_getCropROI(dwBox2D* roi, dwStereoRectifierHandle_t obj);
419 
435 dwStatus dwStereoRectifier_getProjectionMatrix(dwMatrix34f* projectionMat, dwStereoSide side,
436  dwStereoRectifierHandle_t obj);
437 
450  dwStereoRectifierHandle_t obj);
451 
466 dwStatus dwStereoRectifier_getReprojectionMatrix(dwMatrix4f* qMatrix, dwStereoRectifierHandle_t obj);
467 
468 #ifdef __cplusplus
469 }
470 #endif
471 
473 #endif // DW_STEREO_STEREO_H_
Defines a 3x4 matrix of floating point numbers (column major).
Definition: Types.h:263
DW_API_PUBLIC dwStatus dwStereo_setRefinementLevel(uint8_t refinementLvl, dwStereoHandle_t obj)
Sets the refinement level of the ongoing stereo algorithm.
uint32_t levelCount
Number of levels in the pyramid. It must be the same or less than that of the Gaussian pyramid...
Definition: Stereo.h:113
float float32_t
Specifies POD types.
Definition: Types.h:70
NVIDIA DriveWorks API: Rig Configuration
Defines a rectangle.
Definition: Types.h:189
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.
dwStereoCostType initType
Specifies the cost type used for initialization.
Definition: Stereo.h:140
uint32_t width
Input image width (single image).
Definition: Stereo.h:104
dwStereoSide
Side.
Definition: Stereo.h:73
DW_API_PUBLIC dwStatus dwStereo_setOcclusionTest(bool doTest, dwStereoHandle_t obj)
Set occlusion test on/off.
Normalised cross correlation.
Definition: Stereo.h:89
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...
Both sides.
Definition: Stereo.h:79
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.
Defines a CUDA image.
Definition: Image.h:268
Absolute difference and census.
Definition: Stereo.h:95
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_righ...
DW_API_PUBLIC dwStatus dwStereo_getConfidence(const dwImageCUDA **confidenceMap, dwStereoSide side, dwStereoHandle_t obj)
Returns the confidence map for a specified side.
bool holesFilling
Specifies whether to fill invalid pixel using assumption on the scene in order to have a map with 100...
Definition: Stereo.h:134
NVIDIA DriveWorks API: Image Conversion and Streaming Functionality
DW_API_PUBLIC dwStatus dwStereo_setInvalidThreshold(float32_t threshold, dwStereoHandle_t obj)
Set invalidity threshold.
dwStereoCostType
Cost types for matching.
Definition: Stereo.h:85
dwStereoSide side
Side to compute the disparity map of.
Definition: Stereo.h:119
struct dwStereoRectifierObject * dwStereoRectifierHandle_t
A pointer to the handle representing a stereo rectifier.
Definition: Stereo.h:347
Specifies a 3D rigid transformation.
Definition: Types.h:462
Absolute difference.
Definition: Stereo.h:87
uint32_t height
Input image height.
Definition: Stereo.h:107
DW_API_PUBLIC dwStatus dwStereo_release(dwStereoHandle_t obj)
Releases the stereo algorithm.
Configuration parameters for a Stereo algorithm.
Definition: Stereo.h:101
dwStatus
Status definition.
Definition: Status.h:180
float32_t invalidityThreshold
Specifies threshold of invalidity.
Definition: Stereo.h:131
Census transform.
Definition: Stereo.h:93
DW_API_PUBLIC dwStatus dwStereo_setOcclusionInfill(bool doInfill, dwStereoHandle_t obj)
Set occlusion infill on/off.
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.
No scaling, keeps output of rectifier.
Definition: Stereo.h:354
uint8_t refinementLevel
Refinement level (0 no refinement, 1-3)
Definition: Stereo.h:137
Crops to inner valid rectangle.
Definition: Stereo.h:356
DW_API_PUBLIC dwStatus dwStereo_getCUDAStream(cudaStream_t *stream, dwStereoHandle_t obj)
Gets CUDA stream used by the stereo algorithm.
bool occlusionTest
Specifies whether to perform a L/R occlusion test.
Definition: Stereo.h:122
NVIDIA DriveWorks API: Pyramid
Defines a 3x3 matrix of floating point numbers.
Definition: Types.h:237
Defines a 4x4 matrix of floating point numbers (column major).
Definition: Types.h:271
struct dwStereoObject * dwStereoHandle_t
A pointer to the handle representing a stereo algorithm.
Definition: Stereo.h:65
DW_API_PUBLIC dwStatus dwStereo_reset(dwStereoHandle_t obj)
Resets the Stereo module.
uint32_t occlusionThreshold
Threshold for failing the L/R consistency test (in disparity value).
Definition: Stereo.h:125
Pyramid image structure.
Definition: Pyramid.h:64
bool occlusionFilling
Specifies whether to fill occluded pixels for 100% density.
Definition: Stereo.h:128
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:79
dwStereoRectifierCrop
Cropping.
Definition: Stereo.h:352
DW_API_PUBLIC dwStatus dwStereo_computeDisparity(const dwPyramidImage *leftPyramid, const dwPyramidImage *rightPyramid, dwStereoHandle_t obj)
Computes the disparity map given the two rectified views.
DW_API_PUBLIC dwStatus dwStereo_setCUDAStream(cudaStream_t stream, dwStereoHandle_t obj)
Sets CUDA stream used by the stereo algorithm.
Sum of absolute differences.
Definition: Stereo.h:91
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&#39;x)/Tx.
uint32_t maxDisparityRange
Maximal displacement when searching for corresponding pixels.
Definition: Stereo.h:110
struct dwCameraModelObject * dwCameraModelHandle_t
A pointer to the handle representing a calibrated camera model.
Definition: CameraModel.h:66
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.
DW_API_PUBLIC dwStatus dwStereo_getDisparity(const dwImageCUDA **disparityMap, dwStereoSide side, dwStereoHandle_t obj)
Returns the disparity map for a specified side.
DW_API_PUBLIC dwStatus dwStereoRectifier_release(dwStereoRectifierHandle_t obj)
Releases the stereo rectifier.
#define DW_API_PUBLIC
Definition: Exports.h:54
uint32_t levelStop
Level of the pyramid where disparity computation ends. It defines the resolution of the output dispar...
Definition: Stereo.h:116
DW_API_PUBLIC dwStatus dwStereo_setInfill(bool doInfill, dwStereoHandle_t obj)
Set invalid infill on/off.
DW_API_PUBLIC dwStatus dwStereo_initParams(dwStereoParams *stereoParams)
Initializes the stereo parameters.
NVIDIA DriveWorks API: Rectifier Methods
DW_API_PUBLIC dwStatus dwStereoRectifier_getRectificationMatrix(dwMatrix3f *rRectMat, dwStereoSide side, dwStereoRectifierHandle_t obj)
Returns a 3x3 rotation matrix for the side specified.