39 #ifndef DW_IMAGEPROCESSING_STEREO_STEREO_H_ 40 #define DW_IMAGEPROCESSING_STEREO_STEREO_H_ 67 #define DW_STEREO_SIDE_COUNT 2 68 #define MAX_ALLOWED_DISPARITY_RANGE 1024 287 dwStereoHandle_t obj);
405 dwStereoRectifierHandle_t obj);
436 dwStereoRectifierHandle_t obj);
450 dwStereoRectifierHandle_t obj);
473 #endif // DW_STEREO_STEREO_H_ 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. It must be the same or less than that of the Gaussian pyramid...
float float32_t
Specifies POD types.
NVIDIA DriveWorks API: Rig Configuration
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).
DW_API_PUBLIC dwStatus dwStereo_setOcclusionTest(bool doTest, dwStereoHandle_t obj)
Set occlusion test on/off.
Normalised cross correlation.
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_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...
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.
dwStereoSide side
Side to compute the disparity map of.
struct dwStereoRectifierObject * dwStereoRectifierHandle_t
A pointer to the handle representing a stereo rectifier.
uint32_t height
Input image height.
DW_API_PUBLIC dwStatus dwStereo_release(dwStereoHandle_t obj)
Releases the stereo algorithm.
Configuration parameters for a Stereo algorithm.
dwStatus
Status definition.
float32_t invalidityThreshold
Specifies threshold of invalidity.
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.
uint8_t refinementLevel
Refinement level (0 no refinement, 1-3)
Crops to inner valid rectangle.
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.
NVIDIA DriveWorks API: Pyramid
Defines a 3x3 matrix of floating point numbers.
Defines a 4x4 matrix of floating point numbers (column major).
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).
bool occlusionFilling
Specifies whether to fill occluded pixels for 100% density.
struct dwContextObject * dwContextHandle_t
Context handle.
dwStereoRectifierCrop
Cropping.
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.
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'x)/Tx.
uint32_t maxDisparityRange
Maximal displacement when searching for corresponding pixels.
struct dwCameraModelObject * dwCameraModelHandle_t
A pointer to the handle representing a calibrated camera model.
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.
uint32_t levelStop
Level of the pyramid where disparity computation ends. It defines the resolution of the output dispar...
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.