NVIDIA DriveOS Linux NSR SDK API Reference

7.0.3.0 Release
Stereo.h
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: Copyright (c) 2015-2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3  * SPDX-License-Identifier: LicenseRef-NvidiaProprietary
4  *
5  * NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
6  * property and proprietary rights in and to this material, related
7  * documentation and any modifications thereto. Any use, reproduction,
8  * disclosure or distribution of this material and related documentation
9  * without an express license agreement from NVIDIA CORPORATION or
10  * its affiliates is strictly prohibited.
11  */
12 
21 #ifndef DW_IMAGEPROCESSING_STEREO_STEREO_H_
22 #define DW_IMAGEPROCESSING_STEREO_STEREO_H_
23 
24 #include <dw/image/Image.h>
25 #include <dw/rig/Rig.h>
26 #include <dw/imageprocessing/geometry/rectifier/Rectifier.h>
27 #include <dw/imageprocessing/pyramid/Pyramid.h>
28 
29 #ifdef __cplusplus
30 extern "C" {
31 #endif
32 
42 // dwStereo
44 
48 typedef struct dwStereoObject* dwStereoHandle_t;
49 
50 #define DW_STEREO_SIDE_COUNT 2
51 #define MAX_ALLOWED_DISPARITY_RANGE 1024
52 
56 typedef enum {
63 } dwStereoSide;
64 
68 typedef enum {
80 
84 typedef struct
85 {
87  uint32_t width;
88 
90  uint32_t height;
91 
94 
96  uint32_t levelCount;
97 
99  uint32_t levelStop;
100 
103 
106 
109 
112 
115 
118 
121 
124 
126 
141 
160 dwStatus dwStereo_initialize(dwStereoHandle_t* obj, uint32_t width, uint32_t height,
161  const dwStereoParams* stereoParams, dwContextHandle_t ctx);
162 
180  const dwPyramidImage* rightPyramid, dwStereoHandle_t obj);
181 
200 
219 
234 
249 
264 
279 
297 
313 dwStatus dwStereo_getSize(uint32_t* dispWidth, uint32_t* dispHeight, uint32_t gLevel,
315 
331 
346 dwStatus dwStereo_getCUDAStream(cudaStream_t* stream, dwStereoHandle_t obj);
347 
363 
383 
385 // dwStereoRectifier
386 
390 typedef struct dwStereoRectifierObject* dwStereoRectifierHandle_t;
391 
395 typedef enum {
401 
422  dwCameraModelHandle_t cameraRight, dwTransformation3f leftToRig,
424 
439 
458 dwStatus dwStereoRectifier_rectify(dwImageCUDA* outputImageLeft, dwImageCUDA* outputImageRight,
459  const dwImageCUDA* inputImageLeft, const dwImageCUDA* inputImageRight,
461 
478 
500 
518 
538 
539 #ifdef __cplusplus
540 }
541 #endif
542 
544 #endif // DW_STEREO_STEREO_H_
DW_STEREO_COST_NCC
@ DW_STEREO_COST_NCC
Normalised cross correlation.
Definition: Stereo.h:72
dwStereoParams::occlusionThreshold
uint32_t occlusionThreshold
Threshold for failing the L/R consistency test (in disparity value).
Definition: Stereo.h:108
dwCameraModelHandle_t
struct dwCameraModelObject * dwCameraModelHandle_t
A pointer to the handle representing a calibrated camera model.
Definition: CameraModel.h:50
DW_STEREO_COST_CENSUS
@ DW_STEREO_COST_CENSUS
Census transform.
Definition: Stereo.h:76
dwStereo_initParams
DW_API_PUBLIC dwStatus dwStereo_initParams(dwStereoParams *stereoParams)
Initializes the stereo parameters.
DW_STEREO_COST_AD
@ DW_STEREO_COST_AD
Absolute difference.
Definition: Stereo.h:70
dwStereoSide
dwStereoSide
Side.
Definition: Stereo.h:56
dwStereoParams::levelStop
uint32_t levelStop
Level of the pyramid where disparity computation ends. It defines the resolution of the output dispar...
Definition: Stereo.h:99
dwMatrix4f
Defines a 4x4 matrix of floating point numbers (column major) by using only one array.
Definition: MatrixTypes.h:178
dwPyramidImage
Pyramid image structure.
Definition: Pyramid_1.h:47
dwStereoRectifier_getRectificationMatrix
DW_API_PUBLIC dwStatus dwStereoRectifier_getRectificationMatrix(dwMatrix3f *rRectMat, dwStereoSide side, dwStereoRectifierHandle_t obj)
Returns a 3x3 rotation matrix for the side specified.
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.
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.
ctx
DW_API_PUBLIC dwPointCloudRangeImageCreatorParams const *const const dwContextHandle_t ctx
Definition: PointCloudRangeImageCreator.h:293
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.
dwStereoParams
Configuration parameters for a Stereo algorithm.
Definition: Stereo.h:84
DW_STEREO_RECTIFIER_CROP
@ DW_STEREO_RECTIFIER_CROP
Crops to inner valid rectangle.
Definition: Stereo.h:399
dwStereoParams::refinementLevel
uint8_t refinementLevel
Refinement level (0 no refinement, 1-3)
Definition: Stereo.h:120
dwStereo_setRefinementLevel
DW_API_PUBLIC dwStatus dwStereo_setRefinementLevel(uint8_t refinementLvl, dwStereoHandle_t obj)
Sets the refinement level of the ongoing stereo algorithm.
dwStereoRectifierHandle_t
struct dwStereoRectifierObject * dwStereoRectifierHandle_t
A pointer to the handle representing a stereo rectifier.
Definition: Stereo.h:390
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_righ...
dwStereoParams::occlusionTest
bool occlusionTest
Specifies whether to perform a L/R occlusion test.
Definition: Stereo.h:105
dwStereoCostType
dwStereoCostType
Cost types for matching.
Definition: Stereo.h:68
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.
DW_STEREO_SIDE_RIGHT
@ DW_STEREO_SIDE_RIGHT
Right.
Definition: Stereo.h:60
dwStereoParams::invalidityThreshold
float32_t invalidityThreshold
Specifies threshold of invalidity.
Definition: Stereo.h:114
DW_STEREO_SIDE_LEFT
@ DW_STEREO_SIDE_LEFT
Left.
Definition: Stereo.h:58
dwStereo_setOcclusionInfill
DW_API_PUBLIC dwStatus dwStereo_setOcclusionInfill(bool doInfill, dwStereoHandle_t obj)
Set occlusion infill on/off.
dwStereo_reset
DW_API_PUBLIC dwStatus dwStereo_reset(dwStereoHandle_t obj)
Resets the Stereo module.
dwImageCUDA
Defines a CUDA image.
Definition: Image.h:508
float32_t
float float32_t
Specifies POD types.
Definition: BasicTypes.h:41
dwStereoParams::initType
dwStereoCostType initType
Specifies the cost type used for initialization.
Definition: Stereo.h:123
dwRect
Defines a rectangle.
Definition: GeometricTypes.h:47
dwStereo_setCUDAStream
DW_API_PUBLIC dwStatus dwStereo_setCUDAStream(cudaStream_t stream, dwStereoHandle_t obj)
Sets CUDA stream used by the stereo algorithm.
dwStereoParams::levelCount
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:96
dwStereo_getConfidence
DW_API_PUBLIC dwStatus dwStereo_getConfidence(const dwImageCUDA **confidenceMap, dwStereoSide side, dwStereoHandle_t obj)
Returns the confidence map for a specified side.
dwStereo_setInvalidThreshold
DW_API_PUBLIC dwStatus dwStereo_setInvalidThreshold(float32_t threshold, dwStereoHandle_t obj)
Set invalidity threshold.
dwStereoParams::width
uint32_t width
Input image width (single image).
Definition: Stereo.h:87
dwStereo_release
DW_API_PUBLIC dwStatus dwStereo_release(dwStereoHandle_t obj)
Releases the stereo algorithm.
dwMatrix34f
Defines a 3x4 matrix of floating point numbers (column major) by using only one array.
Definition: MatrixTypes.h:189
dwStereoRectifier_release
DW_API_PUBLIC dwStatus dwStereoRectifier_release(dwStereoRectifierHandle_t obj)
Releases the stereo rectifier.
DW_STEREO_COST_ADCENSUS
@ DW_STEREO_COST_ADCENSUS
Absolute difference and census.
Definition: Stereo.h:78
DW_STEREO_RECTIFIER_UNCHANGED
@ DW_STEREO_RECTIFIER_UNCHANGED
No scaling, keeps output of rectifier.
Definition: Stereo.h:397
dwStereoParams::height
uint32_t height
Input image height.
Definition: Stereo.h:90
dwStereoHandle_t
struct dwStereoObject * dwStereoHandle_t
A pointer to the handle representing a stereo algorithm.
Definition: Stereo.h:48
dwStereo_getCUDAStream
DW_API_PUBLIC dwStatus dwStereo_getCUDAStream(cudaStream_t *stream, dwStereoHandle_t obj)
Gets CUDA stream used by the stereo algorithm.
dwContextHandle_t
struct dwContextObject * dwContextHandle_t
Context handle.
Definition: Context.h:74
dwMatrix3f
Defines a 3x3 matrix of floating point numbers by using only one array.
Definition: MatrixTypes.h:158
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,...
dwStatus
dwStatus
Status definition.
Definition: ErrorDefs.h:27
dwStereoParams::occlusionFilling
bool occlusionFilling
Specifies whether to fill occluded pixels for 100% density.
Definition: Stereo.h:111
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.
dwStereoParams::holesFilling
bool holesFilling
Specifies whether to fill invalid pixel using assumption on the scene in order to have a map with 100...
Definition: Stereo.h:117
dwStereoRectifierCrop
dwStereoRectifierCrop
Cropping.
Definition: Stereo.h:395
dwTransformation3f
Specifies a 3D rigid transformation.
Definition: MatrixTypes.h:226
dwStereoParams::maxDisparityRange
uint32_t maxDisparityRange
Maximal displacement when searching for corresponding pixels.
Definition: Stereo.h:93
DW_API_PUBLIC
#define DW_API_PUBLIC
Definition: Exports.h:38
DW_STEREO_COST_SAD
@ DW_STEREO_COST_SAD
Sum of absolute differences.
Definition: Stereo.h:74
obj
const NvSciSyncObj *const obj
Definition: wfdext.h:120
dwStereo_setOcclusionTest
DW_API_PUBLIC dwStatus dwStereo_setOcclusionTest(bool doTest, dwStereoHandle_t obj)
Set occlusion test on/off.
dwStereo_getDisparity
DW_API_PUBLIC dwStatus dwStereo_getDisparity(const dwImageCUDA **disparityMap, dwStereoSide side, dwStereoHandle_t obj)
Returns the disparity map for a specified side.
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.
DW_STEREO_SIDE_BOTH
@ DW_STEREO_SIDE_BOTH
Both sides.
Definition: Stereo.h:62
dwStereo_setInfill
DW_API_PUBLIC dwStatus dwStereo_setInfill(bool doInfill, dwStereoHandle_t obj)
Set invalid infill on/off.
dwStereoParams::side
dwStereoSide side
Side to compute the disparity map of.
Definition: Stereo.h:102