Triclops SDK
4.0.3.0
Functions
Stereo processing functions

Functions

enum TriclopsError triclopsGetDisparity (const TriclopsContext context, int *minDisparity, int *maxDisparity)
 Retrieves the current stereo disparity range. More...
 
enum TriclopsError triclopsGetDoStereo (const TriclopsContext context, TriclopsBool *on)
 Retrieves the current stereo computation status for a context. More...
 
enum TriclopsError triclopsGetStereoAlgorithm (const TriclopsContext context, TriclopsStereoAlgorithm *algorithm)
 Retrieves the current stereo algorithm. More...
 
enum TriclopsError triclopsGetStereoMask (const TriclopsContext context, int *size)
 Retrieves the current stereo mask size. More...
 
enum TriclopsError triclopsSetAnyStereoMask (TriclopsContext context, int size)
 Sets a new stereo mask size ignoring the limits set in the library. More...
 
enum TriclopsError triclopsSetDisparity (TriclopsContext context, int minDisparity, int maxDisparity)
 Sets a new stereo disparity range. More...
 
enum TriclopsError triclopsSetDoStereo (TriclopsContext context, TriclopsBool on)
 Switches stereo computation on or off. More...
 
enum TriclopsError triclopsSetStereoAlgorithm (const TriclopsContext context, TriclopsStereoAlgorithm algorithm)
 Sets a new stereo algorithm. More...
 
enum TriclopsError triclopsSetStereoMask (TriclopsContext context, int masksize)
 Sets a new stereo mask size. More...
 
enum TriclopsError triclopsStereo (TriclopsContext context)
 Performs depth computation and pixel validations. More...
 

Detailed Description

Stereo

The purpose of stereo vision is to perform range measurements based on images obtained from slightly offset cameras. There are three steps in performing stereo processing:

  1. Establish correspondence between image features in different views of the scene.
  2. Calculate the relative displacement between feature coordinates in each image.
  3. Determine the 3D location of the feature relative to the cameras, using the knowledge of the camera geometry.

Consider the following example. The figure below shows an image pair obtained from the horizontally displaced cameras of the Triclops camera module. We can identify two points A and B in both images. The point Aleft corresponds to the point Aright. Similarly, point Bleft corresponds to the point Bright.

stereo_example_01.png
Example of matching points between stereo images

Figure 1: Example of matching points between stereo images

Using a ruler, if you measure out the horizontal distance between the left edge of the images and the points, you will find that distances in the left image are greater than the distance to the corresponding point in the right image. For example, the distance to the phone handle from the left edge of the image is greater than the distance to the phone handle in the right image. Based on this distance (also called disparity) it is possible to determine the distance to the phone handle from the camera module.

We will define the disparity as the difference between the coordinates of the same features in the left and right image. You will find that the distances from the top of the image to the matching features are exactly the same in both images. This is because the cameras are horizontally aligned, therefore only the horizontal displacement is relevant.

Disparity for the feature A will be defined as D(A) = x(Aleft) – x(Aright) and the disparity of point B will be derived as D(B) = x(Bleft) – x(Bright), where x(Aleft) is the x coordinate of the point Aleft.

In this case D(B) > D(A), as point B in the scene is closer than point A.

Establishing Correspondence

The Triclops library establishes correspondence between images using the Sum of Absolute Differences correlation method. The intuition behind the approach is to do the following:

  1. For every pixel in the image
  2. Select a neighborhood of a given square size from the reference image
  3. Compare this neighborhood to a number of neighborhoods in the other image (along the same row)
  4. Select the best match
  5. End

Comparison of neighborhoods or masks is done using the following formula:

stereo_formula_01.png
Sum of absolute differences

Calculating Distances

The distances from the cameras are determined using the displacement between images and the geometry of the cameras. The position of the matched feature is a function of the displacement, the focal length of the lenses, resolution of the sensor and the displacement between sensors.

The Triclops library provides various functions that convert disparities into 3D points, which can be found in group Disparities to 3D coordinates transformation functions.

The figure below illustrates the coordinate system in which the Triclops library represents images and the world measurements. The origin of the image is in the top left corner of the upright image. The origin of the world measurements is in the pinhole of the reference camera.

stereo_3D_01.png
Image and world coordinate systems in the Triclops library

Depth maps bit-depth

Only 16-bits depth maps are computed using subpixel interpolation. 12 bits are reserved for the integer part of disparity, whereas 4 bits are reserved for the fractional part. The maximum disparity value allowed is 4078.

Function Documentation

enum TriclopsError triclopsGetDisparity ( const TriclopsContext  context,
int *  minDisparity,
int *  maxDisparity 
)

Retrieves the current stereo disparity range.

Parameters
contextThe context from which to get the disparity range
minDisparityThe minimum disparity to compute
maxDisparityHow many disparities to compute
Returns
An error code representing the outcome of the function
Return values
TriclopsErrorOkThe function completed successfully
TriclopsErrorInvalidContextThe provided context is invalid
See also
triclopsSetDisparity()
enum TriclopsError triclopsGetDoStereo ( const TriclopsContext  context,
TriclopsBool on 
)

Retrieves the current stereo computation status for a context.

Parameters
contextThe context from which to get the status of stereo computation
onThe retrieved status
Returns
An error code representing the outcome of the function
Return values
TriclopsErrorOkThe function completed successfully
TriclopsErrorInvalidContextThe provided context is invalid
See also
triclopsSetDoStereo()
enum TriclopsError triclopsGetStereoAlgorithm ( const TriclopsContext  context,
TriclopsStereoAlgorithm algorithm 
)

Retrieves the current stereo algorithm.

Parameters
contextThe context for which to set the stereo algorithm
algorithmThe stereo algorithm in use by the provided context
Returns
An error code representing the outcome of the function
Return values
TriclopsErrorOkThe function completed successfully
TriclopsErrorInvalidContextThe provided context is invalid
See also
triclopsSetStereoAlgorithm()
enum TriclopsError triclopsGetStereoMask ( const TriclopsContext  context,
int *  size 
)

Retrieves the current stereo mask size.

Parameters
contextThe context from which to set the stereo mask size
sizeThe retrieved mask size
Returns
An error code representing the outcome of the function
Return values
TriclopsErrorOkThe function completed successfully
TriclopsErrorInvalidContextThe provided context is invalid
See also
triclopsSetStereoMask()
enum TriclopsError triclopsSetAnyStereoMask ( TriclopsContext  context,
int  size 
)

Sets a new stereo mask size ignoring the limits set in the library.

This function allows the user to set an arbitrary stereo mask. This can lead to a number of unpredictable behaviours, such as overflowing or random disparities.

Parameters
contextThe context for which to set the stereo mask size
sizeThe new mask size, which needs to be an odd number
Returns
An error code representing the outcome of the function
Return values
TriclopsErrorOkThe function completed successfully
TriclopsErrorInvalidContextThe provided context is invalid
TriclopsErrorInvalidSettingThe provided mask size is invalid
See also
triclopsGetStereoMask()
enum TriclopsError triclopsSetDisparity ( TriclopsContext  context,
int  minDisparity,
int  maxDisparity 
)

Sets a new stereo disparity range.

The maximum disparity range that can be set is currently 4078.

Parameters
contextThe context for which to set the new disparity range
minDisparityThe minimum disparity to compute
maxDisparityHow many disparities to compute
Returns
An error code representing the outcome of the function
Return values
TriclopsErrorOkThe function completed successfully
TriclopsErrorInvalidContextThe provided context is invalid
TriclopsErrorInvalidNumberDisparitiesThe provided number of disparities is invalid (i.e. less or equal than zero)
TriclopsErrorInvalidSettingThe combination of minDisparity and maxDisparity is invalid (e.g. negative minDisparity, maximum computed disparity too big, needed offset is too big).
See also
triclopsGetDisparity()
triclopsSetDoStereo()
enum TriclopsError triclopsSetDoStereo ( TriclopsContext  context,
TriclopsBool  on 
)

Switches stereo computation on or off.

triclopsStereo() will return TriclopsErrorOk without doing nothing if stereo computation is set to off

Parameters
contextThe context for which to enable/disable stereo computation
onWhether stereo computation should be on or off
Returns
An error code representing the outcome of the function
Return values
TriclopsErrorOkThe function completed successfully
TriclopsErrorInvalidContextThe provided context is invalid
See also
triclopsGetDoStereo()
enum TriclopsError triclopsSetStereoAlgorithm ( const TriclopsContext  context,
TriclopsStereoAlgorithm  algorithm 
)

Sets a new stereo algorithm.

Parameters
contextThe context for which to set the stereo algorithm
algorithmThe new stereo algorithm to use
Returns
An error code representing the outcome of the function
Return values
TriclopsErrorOkThe function completed successfully
TriclopsErrorInvalidContextThe provided context is invalid
See also
triclopsGetStereoAlgorithm()
enum TriclopsError triclopsSetStereoMask ( TriclopsContext  context,
int  masksize 
)

Sets a new stereo mask size.

Parameters
contextThe context for which to set the stereo mask size
masksizeThe new mask size, which needs to be an odd number between 1 and 23
Returns
An error code representing the outcome of the function
Return values
TriclopsErrorOkThe function completed successfully
TriclopsErrorInvalidContextThe provided context is invalid
TriclopsErrorInvalidSettingThe provided mask size is invalid
See also
triclopsGetStereoMask()
enum TriclopsError triclopsStereo ( TriclopsContext  context)

Performs depth computation and pixel validations.

This function performs stereo processing and validations based on the parameters set in the provided context. The resulting depth map is stored inside the provided context and can be retrieved using triclopsGetImage16().

This function returns an error if neither triclopsRectify() nor triclopsColorRectify() has been previously called.

Parameters
contextThe context on which to perform depth computation
Returns
An error code representing the outcome of the function
Return values
TriclopsErrorOkThe function completed successfully
TriclopsErrorRectificationNotProcessedThis function has been called before calling triclopsRectify() or triclopsColorRectify()
TriclopsErrorInvalidCameraConfigThe stereo algorithm set in the provided context is non-existant (i.e. wrong triclopsSetStereoAlgorithm() parameter)
TriclopsErrorInvalidStereoROIThe ROI requested, combined with stereo and edge mask, is invalid (e.g. the resulting area is too small)
TriclopsErrorUnknownThe stereo process has encountered a problem during computation and failed. This error is returned only when selecting OpenCV for stereo computations.
See also
triclopsGetImage()
triclopsSetStereoMask()
triclopsSetDoStereo()
Contact Support Triclops SDK Programmer's Guide and API Reference