Public Member Functions | Private Member Functions | Private Attributes
CStereoMatcher Class Reference

Class for computing matches for individual points in stereo image pairs. More...

#include <StereoMatcher.h>

List of all members.

Public Member Functions

 CStereoMatcher ()
 The default constructor (and only constructor).
int GetDisparityEstimate (const float z)
 Computes a disparity estimated for a given z-distance.
void InitCameraParameters (CStereoCalibration *pStereoCalibration, bool bCloneCalibration)
 Initializes the internally used camera model, given an instance of CStereoCalibration.
bool LoadCameraParameters (const char *pCameraParameterFileName)
 Initializes the internally used camera model, given a file path to a camera parameter file.
int Match (const CByteImage *pLeftImage, const CByteImage *pRightImage, int x, int y, int nWindowSize, int d1, int d2, Vec2d &result, Vec3d &result_3d, float fThreshold, bool bInputImagesAreUndistorted=false)
 Computes a disparity estimated for a given z-distance using the Zero-Mean Normalized Cross Correlation (ZNCC).
int MatchZSAD (const CByteImage *pLeftImage, const CByteImage *pRightImage, int x, int y, int nWindowSize, int d1, int d2, Vec2d &result, Vec3d &result_3d, float fThreshold, bool bInputImagesAreUndistorted=false)
 Computes a disparity estimated for a given z-distance using the Zero-Mean Sum of Absolute Differences (ZSAD).
 ~CStereoMatcher ()
 The destructor.

Private Member Functions

int SingleZNCC (const CByteImage *pInputImage1, const CByteImage *pInputImage2, int x, int y, int nWindowSize, int d1, int d2, float *values)
int SingleZSAD (const CByteImage *pInputImage1, const CByteImage *pInputImage2, int x, int y, int nWindowSize, int d1, int d2, float *values)

Private Attributes

bool m_bOwnStereoCalibrationObject
CStereoCalibrationm_pStereoCalibration

Detailed Description

Class for computing matches for individual points in stereo image pairs.

This class allows to search for a correspondence in the right image, given a point in the left image of stereo image pair. As correlation function a Zero-Mean Normalized Cross Correlation (ZNCC) is used. The ZNCC is invariant to constant additive and constant multiplicative illumination variations.

The search for the correspondences is performed along the epipolar line. The images must not be rectified (or if rectified, the camera parameters must be updated to be valid for the rectified images). In any case it is recommended to provide the original images - not rectified images.

As result, the corresponence in the right image is computed with subpixel accuracy as well as the 3D point in the world coordinate system by performing stereo triangulation.

Images must be of type CByteImage::eGrayScale.

Definition at line 78 of file StereoMatcher.h.


Constructor & Destructor Documentation

The default constructor (and only constructor).

Initialization is performed by calling one of the methods LoadCameraParameters(const char*) or InitCameraParameters(CStereoCalibration*, bool).

Definition at line 67 of file StereoMatcher.cpp.

The destructor.

Definition at line 73 of file StereoMatcher.cpp.


Member Function Documentation

int CStereoMatcher::GetDisparityEstimate ( const float  z)

Computes a disparity estimated for a given z-distance.

The z-distance is defined as the z-coordinate in the camera coordinate system of the left camera. The disparity estimate is computed as the disparity of the point (0, 0, z)^T in the camera coordinate system of the left camera.

Before application of this method, the instance must have been initialized by calling one of the methods LoadCameraParameters(const char*) or InitCameraParameters(CStereoCalibration*, bool).

Parameters:
[in]zThe z-distance to compute the disparity estimate for.
Returns:
the disparity estimate in pixels.

Definition at line 112 of file StereoMatcher.cpp.

void CStereoMatcher::InitCameraParameters ( CStereoCalibration pStereoCalibration,
bool  bCloneCalibration 
)

Initializes the internally used camera model, given an instance of CStereoCalibration.

The camera parameters are needed for knowledge of the epipolar geometry.

Parameters:
[in]pStereoCalibrationThe pointer to the instance of CStereoCalibration.
[in]bCloneCalibrationIf set to true, an internal instance is created and pStereoCalibration serves as the template instance. If set to false simply the pointer is stored. In any case, deletion of the provided instance pStereoCalibration is not handled by CStereoMatcher.

Definition at line 92 of file StereoMatcher.cpp.

bool CStereoMatcher::LoadCameraParameters ( const char *  pCameraParameterFileName)

Initializes the internally used camera model, given a file path to a camera parameter file.

The file must contain the parameters for the used stereo camera system. Details on the file format and camera calibration can be found in CStereoCalibration::LoadCameraParameters.

The camera parameters are needed for knowledge of the epipolar geometry.

Parameters:
[in]pCameraParameterFileNameThe file path to the camera parameter file to be loaded.
Returns:
true on success and false on failure.

Definition at line 84 of file StereoMatcher.cpp.

int CStereoMatcher::Match ( const CByteImage pLeftImage,
const CByteImage pRightImage,
int  x,
int  y,
int  nWindowSize,
int  d1,
int  d2,
Vec2d result,
Vec3d result_3d,
float  fThreshold,
bool  bInputImagesAreUndistorted = false 
)

Computes a disparity estimated for a given z-distance using the Zero-Mean Normalized Cross Correlation (ZNCC).

The z-distance is defined as the z-coordinate in the camera coordinate system of the left camera. The disparity estimate is computed as the disparity of the point (0, 0, z)^T in the camera coordinate system of the left camera.

The width and height of pInputImage and pOutputImage must match. pInputImage and pOutputImage must be both of type CByteImage::eGrayScale.

Before application of this method, the instance must have been initialized by calling one of the methods LoadCameraParameters(const char*) or InitCameraParameters(CStereoCalibration*, bool).

Parameters:
[in]pLeftImageThe left camera image. Must be of type CByteImage::eGrayScale.
[in]pRightImageThe right camera image. Must be of type CByteImage::eGrayScale.
[in]xThe x-coordinate of the point in pLeftImage to search a correspondence for in pRightImage.
[in]yThe y-coordinate of the point in pLeftImage to search a correspondence for in pRightImage.
[in]nWindowSizeSpecifies the size of the correlation window, which is nWindowSize x nWindowSize.
[in]d1The minimum disparity, defining the starting point of the search. Must be >= 0.
[in]d2The maximum disparity, defining the end point of the search. Must be > d1.
[out]resultThe computed correspondence in the pRightImage, with subpixel accuracy.
[out]result_3dThe computed 3D point, expressed in the world coordinate system.
[in]fThresholdThe threshold for the Zero Mean-Normalized Cross Correlation (ZNCC). As the ZNCC is a similarity measure (not an error measure) the greater the value the greater is the similarity. The maximum value that can be achieved is 1. fThreshold = 0.0f practically accepts all correspondences, fThreshold = 0.5f can be considered as a relatively non-restrictive threshold, fThrehold = 0.8f can be considered as a relatively restrictive threshold. The choice of this value depends on the quality of the images and the application.
[in]bInputImagesAreUndistortedIf set to false (default value) the input coordinates are undistorted before performing the search. If set to true, it is assumed that the images are already undistorted, thus not undistorting the coordinates.
As the epipolar geometry is only valid for the linear mapping, it is strictly recommended to undistort the images, if the lens distortions have an observable effect.
Returns:
the disparity >= 0 in case of success. Returns -1 if the images (equal size, type) do not meet the conditions. Returns -2 if no match could be found.

Definition at line 125 of file StereoMatcher.cpp.

int CStereoMatcher::MatchZSAD ( const CByteImage pLeftImage,
const CByteImage pRightImage,
int  x,
int  y,
int  nWindowSize,
int  d1,
int  d2,
Vec2d result,
Vec3d result_3d,
float  fThreshold,
bool  bInputImagesAreUndistorted = false 
)

Computes a disparity estimated for a given z-distance using the Zero-Mean Sum of Absolute Differences (ZSAD).

The z-distance is defined as the z-coordinate in the camera coordinate system of the left camera. The disparity estimate is computed as the disparity of the point (0, 0, z)^T in the camera coordinate system of the left camera.

The width and height of pInputImage and pOutputImage must match. pInputImage and pOutputImage must be both of type CByteImage::eGrayScale.

Before application of this method, the instance must have been initialized by calling one of the methods LoadCameraParameters(const char*) or InitCameraParameters(CStereoCalibration*, bool).

Parameters:
[in]pLeftImageThe left camera image. Must be of type CByteImage::eGrayScale.
[in]pRightImageThe right camera image. Must be of type CByteImage::eGrayScale.
[in]xThe x-coordinate of the point in pLeftImage to search a correspondence for in pRightImage.
[in]yThe y-coordinate of the point in pLeftImage to search a correspondence for in pRightImage.
[in]nWindowSizeSpecifies the size of the correlation window, which is nWindowSize x nWindowSize.
[in]d1The minimum disparity, defining the starting point of the search. Must be >= 0.
[in]d2The maximum disparity, defining the end point of the search. Must be > d1.
[out]resultThe computed correspondence in the pRightImage, with subpixel accuracy.
[out]result_3dThe computed 3D point, expressed in the world coordinate system.
[in]fThresholdThe threshold for the Zero-Mean Sum of Absolute Differences (ZSAD). As the ZSAD is an error measure, the smaller the value the greater is the similarity. The minimum value that can be achieved is 0. fThreshold = 255.0f accepts all correspondences. The choice of this value depends on the quality of the images and the application.
[in]bInputImagesAreUndistortedIf set to false (default value) the input coordinates are undistorted before performing the search. If set to true, it is assumed that the images are already undistorted, thus not undistorting the coordinates.
As the epipolar geometry is only valid for the linear mapping, it is strictly recommended to undistort the images, if the lens distortions have an observable effect.
Returns:
the disparity >= 0 in case of success. Returns -1 if the images (equal size, type) do not meet the conditions. Returns -2 if no match could be found.

Definition at line 169 of file StereoMatcher.cpp.

int CStereoMatcher::SingleZNCC ( const CByteImage pInputImage1,
const CByteImage pInputImage2,
int  x,
int  y,
int  nWindowSize,
int  d1,
int  d2,
float *  values 
) [private]

Definition at line 214 of file StereoMatcher.cpp.

int CStereoMatcher::SingleZSAD ( const CByteImage pInputImage1,
const CByteImage pInputImage2,
int  x,
int  y,
int  nWindowSize,
int  d1,
int  d2,
float *  values 
) [private]

Definition at line 330 of file StereoMatcher.cpp.


Member Data Documentation

Definition at line 203 of file StereoMatcher.h.

Definition at line 202 of file StereoMatcher.h.


The documentation for this class was generated from the following files:


asr_ivt
Author(s): Allgeyer Tobias, Hutmacher Robin, Kleinert Daniel, Meißner Pascal, Scholz Jonas, Stöckle Patrick
autogenerated on Thu Jun 6 2019 21:46:58