39 #ifndef DW_STEREO_STEREO_H__ 40 #define DW_STEREO_STEREO_H__ 66 #define DW_STEREO_SIDE_COUNT 2 67 #define MAX_ALLOWED_DISPARITY_RANGE 1024 285 dwStereoHandle_t obj);
400 dwStereoRectifierHandle_t obj);
431 dwStereoRectifierHandle_t obj);
445 dwStereoRectifierHandle_t obj);
471 #endif // DW_STEREO_STEREO_H__ dwBool occlusionTest
Specifies whether to perform a L/R occlusion test.
NVIDIA DriveWorks API: Rig Configuration
Defines a 3x4 matrix of floating point numbers (column major).
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.
float float32_t
Specifies POD types.
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.
uint32_t width
Input image width (single image).
dwBool occlusionFilling
Specifies whether to fill occluded pixels for 100% density.
Normalised cross correlation.
dwBool refinementLevel
Refinement level (0 no refinement, 1-3)
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...
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.
Absolute difference and census.
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.
dwStereoSide side
Side to compute the disparity map of.
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.
uint32_t height
Input image height.
NVIDIA DriveWorks API: Image Conversion and Streaming Functionality
Configuration parameters for a Stereo algorithm.
dwStatus
Status definition.
float32_t invalidityThreshold
Specifies threshold of invalidity.
No scaling, keeps output of rectifier.
Crops to inner valid rectangle.
struct dwCalibratedCameraObject * dwCalibratedCameraHandle_t
A pointer to the handle representing a calibrated camera.
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.
struct dwStereoObject * dwStereoHandle_t
A pointer to the handle representing a stereo algorithm.
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).
struct dwPyramidObject const * dwConstPyramidHandle_t
Handle representing a const image pyramid.
DW_API_PUBLIC dwStatus dwStereo_setInfill(dwBool doInfill, dwStereoHandle_t obj)
Set invalid infill on/off.
struct dwContextObject * dwContextHandle_t
Context handle.
dwStereoRectifierCrop
Cropping.
dwBool holesFilling
Specifies whether to fill invalid pixel using assumption on the scene.
DW_API_PUBLIC dwStatus dwStereo_setCUDAStream(cudaStream_t stream, dwStereoHandle_t obj)
Sets CUDA stream used by the stereo algorithm.
Sum of absolute differences.
NVIDIA DriveWorks API: 2D Tracker
uint32_t maxDisparityRange
Maximum disparity range.
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'x)/Tx.
uint32_t levelStop
Level of the pyramid where disparity computation ends (starts from levelCount-1 -> 0)...
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.