DriveWorks SDK Reference

| 0.6.67 Release

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-2017 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_STEREO_STEREO_H__
40 #define DW_STEREO_STEREO_H__
41 
42 #include <dw/image/Image.h>
44 #include <dw/rectifier/Rectifier.h>
45 #include <dw/features/Features.h>
46 
47 #ifdef __cplusplus
48 extern "C" {
49 #endif
50 
58 // dwStereo
60 
64 typedef struct dwStereoObject *dwStereoHandle_t;
65 
66 #define DW_STEREO_SIDE_COUNT 2
67 #define MAX_ALLOWED_DISPARITY_RANGE 1024
68 
72 typedef enum {
79 } dwStereoSide;
80 
84 typedef enum {
96 
100 typedef struct {
102  uint32_t width;
103 
105  uint32_t height;
106 
109 
111  uint32_t levelCount;
112 
114  uint32_t levelStop;
115 
117  dwStereoSide side;
118 
121 
124 
127 
130 
133 
136 
138  dwStereoCostType initType;
139 
141 
152 
167 dwStatus dwStereo_initialize(dwStereoHandle_t* obj, uint32_t width, uint32_t height,
168  const dwStereoParams* stereoParams, dwContextHandle_t ctx);
169 
183  dwConstPyramidHandle_t rightPyramid, dwStereoHandle_t obj);
184 
198 dwStatus dwStereo_getDisparity(const dwImageCUDA **disparityMap, dwStereoSide side, dwStereoHandle_t obj);
199 
213 dwStatus dwStereo_getConfidence(const dwImageCUDA** confidenceMap, dwStereoSide side, dwStereoHandle_t obj);
214 
224 dwStatus dwStereo_setOcclusionTest(dwBool doTest, dwStereoHandle_t obj);
225 
235 dwStatus dwStereo_setOcclusionInfill(dwBool doInfill, dwStereoHandle_t obj);
236 
246 dwStatus dwStereo_setInfill(dwBool doInfill, dwStereoHandle_t obj);
247 
257 dwStatus dwStereo_setInvalidThreshold(float32_t threshold, dwStereoHandle_t obj);
258 
271 dwStatus dwStereo_setRefinementLevel(uint8_t refinementLvl, dwStereoHandle_t obj);
272 
284 dwStatus dwStereo_getSize(uint32_t *dispWidth, uint32_t *dispHeight, uint32_t gLevel,
285  dwStereoHandle_t obj);
286 
297 dwStatus dwStereo_setCUDAStream(cudaStream_t stream, dwStereoHandle_t obj);
298 
309 dwStatus dwStereo_getCUDAStream(cudaStream_t *stream, dwStereoHandle_t obj);
310 
319 dwStatus dwStereo_reset(dwStereoHandle_t obj);
320 
333 dwStatus dwStereo_release(dwStereoHandle_t *obj);
334 
336 // dwStereoRectifier
337 
341 typedef struct dwStereoRectifierObject *dwStereoRectifierHandle_t;
342 
346 typedef enum {
352 
368 dwStatus dwStereoRectifier_initialize(dwStereoRectifierHandle_t* obj, dwCalibratedCameraHandle_t cameraLeft,
369  dwCalibratedCameraHandle_t cameraRight, dwTransformation leftToRig,
370  dwTransformation rightToRig, dwContextHandle_t ctx);
371 
381 dwStatus dwStereoRectifier_release(dwStereoRectifierHandle_t* obj);
382 
383 
398 dwStatus dwStereoRectifier_rectify(dwImageCUDA *outputImageLeft, dwImageCUDA *outputImageRight,
399  const dwImageCUDA* inputImageLeft, const dwImageCUDA* inputImageRight,
400  dwStereoRectifierHandle_t obj);
401 
413 dwStatus dwStereoRectifier_getCropROI(dwBox2D *roi, dwStereoRectifierHandle_t obj);
414 
430 dwStatus dwStereoRectifier_getProjectionMatrix(dwMatrix34f *projectionMat, dwStereoSide side,
431  dwStereoRectifierHandle_t obj);
432 
445  dwStereoRectifierHandle_t obj);
446 
461 dwStatus dwStereoRectifier_getReprojectionMatrix(dwTransformation *qMatrix, dwStereoRectifierHandle_t obj);
462 
463 
464 
465 #ifdef __cplusplus
466 }
467 #endif
468 
471 #endif // DW_STEREO_STEREO_H__
dwBool occlusionTest
Specifies whether to perform a L/R occlusion test.
Definition: Stereo.h:120
NVIDIA DriveWorks API: Rig Configuration
Defines a 3x4 matrix of floating point numbers (column major).
Definition: Types.h:195
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.
Definition: Stereo.h:111
float float32_t
Specifies POD types.
Definition: Types.h:77
Defines a rectangle.
Definition: Types.h:151
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:138
uint32_t width
Input image width (single image).
Definition: Stereo.h:102
dwStereoSide
Side.
Definition: Stereo.h:72
dwBool occlusionFilling
Specifies whether to fill occluded pixels for 100% density.
Definition: Stereo.h:126
Normalised cross correlation.
Definition: Stereo.h:88
dwBool refinementLevel
Refinement level (0 no refinement, 1-3)
Definition: Stereo.h:135
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:78
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:263
Absolute difference and census.
Definition: Stereo.h:94
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_computeDisparity(dwConstPyramidHandle_t leftPyramid, dwConstPyramidHandle_t rightPyramid, dwStereoHandle_t obj)
Computes the disparity map given the two rectified views.
DW_API_PUBLIC dwStatus dwStereo_getConfidence(const dwImageCUDA **confidenceMap, dwStereoSide side, dwStereoHandle_t obj)
Returns the confidence map for a specified side.
DW_API_PUBLIC dwStatus dwStereoRectifier_initialize(dwStereoRectifierHandle_t *obj, dwCalibratedCameraHandle_t cameraLeft, dwCalibratedCameraHandle_t cameraRight, dwTransformation leftToRig, dwTransformation rightToRig, dwContextHandle_t ctx)
Initializes the stereo rectifier.
DW_API_PUBLIC dwStatus dwStereo_setInvalidThreshold(float32_t threshold, dwStereoHandle_t obj)
Set invalidity threshold.
dwStereoCostType
Cost types for matching.
Definition: Stereo.h:84
dwStereoSide side
Side to compute the disparity map of.
Definition: Stereo.h:117
DW_API_PUBLIC dwStatus dwStereoRectifier_release(dwStereoRectifierHandle_t *obj)
Releases the stereo rectifier.
DW_API_PUBLIC dwStatus dwStereo_setOcclusionInfill(dwBool doInfill, dwStereoHandle_t obj)
Set occlusion infill on/off.
struct dwStereoRectifierObject * dwStereoRectifierHandle_t
A pointer to the handle representing a stereo rectifier.
Definition: Stereo.h:341
Absolute difference.
Definition: Stereo.h:86
uint32_t height
Input image height.
Definition: Stereo.h:105
NVIDIA DriveWorks API: Image Conversion and Streaming Functionality
Configuration parameters for a Stereo algorithm.
Definition: Stereo.h:100
dwStatus
Status definition.
Definition: Status.h:167
float32_t invalidityThreshold
Specifies threshold of invalidity.
Definition: Stereo.h:129
Census transform.
Definition: Stereo.h:92
No scaling, keeps output of rectifier.
Definition: Stereo.h:348
Crops to inner valid rectangle.
Definition: Stereo.h:350
struct dwCalibratedCameraObject * dwCalibratedCameraHandle_t
A pointer to the handle representing a calibrated camera.
Definition: Camera.h:66
DW_API_PUBLIC dwStatus dwStereo_getCUDAStream(cudaStream_t *stream, dwStereoHandle_t obj)
Gets CUDA stream used by the stereo algorithm.
Defines a 3x3 matrix of floating point numbers.
Definition: Types.h:180
struct dwStereoObject * dwStereoHandle_t
A pointer to the handle representing a stereo algorithm.
Definition: Stereo.h:64
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:123
struct dwPyramidObject const * dwConstPyramidHandle_t
Handle representing a const image pyramid.
Definition: Features.h:76
DW_API_PUBLIC dwStatus dwStereo_setInfill(dwBool doInfill, dwStereoHandle_t obj)
Set invalid infill on/off.
uint8_t dwBool
Definition: Types.h:79
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:78
dwStereoRectifierCrop
Cropping.
Definition: Stereo.h:346
dwBool holesFilling
Specifies whether to fill invalid pixel using assumption on the scene.
Definition: Stereo.h:132
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:90
NVIDIA DriveWorks API: 2D Tracker
uint32_t maxDisparityRange
Maximum disparity range.
Definition: Stereo.h:108
DW_API_PUBLIC dwStatus dwStereo_setOcclusionTest(dwBool doTest, dwStereoHandle_t obj)
Set occlusion test on/off.
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_getReprojectionMatrix(dwTransformation *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.
#define DW_API_PUBLIC
Definition: Exports.h:76
uint32_t levelStop
Level of the pyramid where disparity computation ends (starts from levelCount-1 -> 0)...
Definition: Stereo.h:114
DW_API_PUBLIC dwStatus dwStereo_release(dwStereoHandle_t *obj)
Releases the stereo algorithm.
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.