DriveWorks SDK Reference
3.5.78 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 
61 // dwStereo
63 
67 typedef struct dwStereoObject* dwStereoHandle_t;
68 
69 #define DW_STEREO_SIDE_COUNT 2
70 #define MAX_ALLOWED_DISPARITY_RANGE 1024
71 
75 typedef enum {
82 } dwStereoSide;
83 
87 typedef enum {
99 
103 typedef struct
104 {
106  uint32_t width;
107 
109  uint32_t height;
110 
113 
115  uint32_t levelCount;
116 
118  uint32_t levelStop;
119 
121  dwStereoSide side;
122 
125 
128 
131 
134 
137 
140 
142  dwStereoCostType initType;
143 
145 
156 
171 dwStatus dwStereo_initialize(dwStereoHandle_t* obj, uint32_t width, uint32_t height,
172  const dwStereoParams* stereoParams, dwContextHandle_t ctx);
173 
187  const dwPyramidImage* rightPyramid, dwStereoHandle_t obj);
188 
202 dwStatus dwStereo_getDisparity(const dwImageCUDA** disparityMap, dwStereoSide side, dwStereoHandle_t obj);
203 
217 dwStatus dwStereo_getConfidence(const dwImageCUDA** confidenceMap, dwStereoSide side, dwStereoHandle_t obj);
218 
228 dwStatus dwStereo_setOcclusionTest(bool doTest, dwStereoHandle_t obj);
229 
239 dwStatus dwStereo_setOcclusionInfill(bool doInfill, dwStereoHandle_t obj);
240 
250 dwStatus dwStereo_setInfill(bool doInfill, dwStereoHandle_t obj);
251 
261 dwStatus dwStereo_setInvalidThreshold(float32_t threshold, dwStereoHandle_t obj);
262 
275 dwStatus dwStereo_setRefinementLevel(uint8_t refinementLvl, dwStereoHandle_t obj);
276 
288 dwStatus dwStereo_getSize(uint32_t* dispWidth, uint32_t* dispHeight, uint32_t gLevel,
289  dwStereoHandle_t obj);
290 
301 dwStatus dwStereo_setCUDAStream(cudaStream_t stream, dwStereoHandle_t obj);
302 
313 dwStatus dwStereo_getCUDAStream(cudaStream_t* stream, dwStereoHandle_t obj);
314 
325 dwStatus dwStereo_reset(dwStereoHandle_t obj);
326 
341 dwStatus dwStereo_release(dwStereoHandle_t obj);
342 
344 // dwStereoRectifier
345 
349 typedef struct dwStereoRectifierObject* dwStereoRectifierHandle_t;
350 
354 typedef enum {
360 
376 dwStatus dwStereoRectifier_initialize(dwStereoRectifierHandle_t* obj, dwCameraModelHandle_t cameraLeft,
377  dwCameraModelHandle_t cameraRight, dwTransformation3f leftToRig,
378  dwTransformation3f rightToRig, dwContextHandle_t ctx);
379 
389 dwStatus dwStereoRectifier_release(dwStereoRectifierHandle_t obj);
390 
405 dwStatus dwStereoRectifier_rectify(dwImageCUDA* outputImageLeft, dwImageCUDA* outputImageRight,
406  const dwImageCUDA* inputImageLeft, const dwImageCUDA* inputImageRight,
407  dwStereoRectifierHandle_t obj);
408 
420 dwStatus dwStereoRectifier_getCropROI(dwBox2D* roi, dwStereoRectifierHandle_t obj);
421 
437 dwStatus dwStereoRectifier_getProjectionMatrix(dwMatrix34f* projectionMat, dwStereoSide side,
438  dwStereoRectifierHandle_t obj);
439 
452  dwStereoRectifierHandle_t obj);
453 
468 dwStatus dwStereoRectifier_getReprojectionMatrix(dwMatrix4f* qMatrix, dwStereoRectifierHandle_t obj);
469 
470 #ifdef __cplusplus
471 }
472 #endif
473 
475 #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:115
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:142
uint32_t width
Input image width (single image).
Definition: Stereo.h:106
dwStereoSide
Side.
Definition: Stereo.h:75
DW_API_PUBLIC dwStatus dwStereo_setOcclusionTest(bool doTest, dwStereoHandle_t obj)
Set occlusion test on/off.
Normalised cross correlation.
Definition: Stereo.h:91
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:81
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:266
Absolute difference and census.
Definition: Stereo.h:97
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:136
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:87
dwStereoSide side
Side to compute the disparity map of.
Definition: Stereo.h:121
struct dwStereoRectifierObject * dwStereoRectifierHandle_t
A pointer to the handle representing a stereo rectifier.
Definition: Stereo.h:349
Specifies a 3D rigid transformation.
Definition: Types.h:462
Absolute difference.
Definition: Stereo.h:89
uint32_t height
Input image height.
Definition: Stereo.h:109
DW_API_PUBLIC dwStatus dwStereo_release(dwStereoHandle_t obj)
Releases the stereo algorithm.
Configuration parameters for a Stereo algorithm.
Definition: Stereo.h:103
dwStatus
Status definition.
Definition: Status.h:178
float32_t invalidityThreshold
Specifies threshold of invalidity.
Definition: Stereo.h:133
Census transform.
Definition: Stereo.h:95
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:356
uint8_t refinementLevel
Refinement level (0 no refinement, 1-3)
Definition: Stereo.h:139
Crops to inner valid rectangle.
Definition: Stereo.h:358
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:124
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:67
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:127
Pyramid image structure.
Definition: Pyramid.h:66
bool occlusionFilling
Specifies whether to fill occluded pixels for 100% density.
Definition: Stereo.h:130
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:80
dwStereoRectifierCrop
Cropping.
Definition: Stereo.h:354
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:93
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:112
struct dwCameraModelObject * dwCameraModelHandle_t
A pointer to the handle representing a calibrated camera model.
Definition: CameraModel.h:68
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:56
uint32_t levelStop
Level of the pyramid where disparity computation ends. It defines the resolution of the output dispar...
Definition: Stereo.h:118
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.