|
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...
|
|
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:
- Establish correspondence between image features in different views of the scene.
- Calculate the relative displacement between feature coordinates in each image.
- 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
.
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:
- For every pixel in the image
- Select a neighborhood of a given square size from the reference image
- Compare this neighborhood to a number of neighborhoods in the other image (along the same row)
- Select the best match
- End
Comparison of neighborhoods or masks is done using the following formula:
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.
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.
Retrieves the current stereo disparity range.
- Parameters
-
context | The context from which to get the disparity range |
minDisparity | The minimum disparity to compute |
maxDisparity | How many disparities to compute |
- Returns
- An error code representing the outcome of the function
- Return values
-
TriclopsErrorOk | The function completed successfully |
TriclopsErrorInvalidContext | The provided context is invalid |
- See also
- triclopsSetDisparity()
Retrieves the current stereo computation status for a context.
- Parameters
-
context | The context from which to get the status of stereo computation |
on | The retrieved status |
- Returns
- An error code representing the outcome of the function
- Return values
-
TriclopsErrorOk | The function completed successfully |
TriclopsErrorInvalidContext | The provided context is invalid |
- See also
- triclopsSetDoStereo()
Retrieves the current stereo algorithm.
- Parameters
-
context | The context for which to set the stereo algorithm |
algorithm | The stereo algorithm in use by the provided context |
- Returns
- An error code representing the outcome of the function
- Return values
-
TriclopsErrorOk | The function completed successfully |
TriclopsErrorInvalidContext | The provided context is invalid |
- See also
- triclopsSetStereoAlgorithm()
Retrieves the current stereo mask size.
- Parameters
-
context | The context from which to set the stereo mask size |
size | The retrieved mask size |
- Returns
- An error code representing the outcome of the function
- Return values
-
TriclopsErrorOk | The function completed successfully |
TriclopsErrorInvalidContext | The provided context is invalid |
- See also
- triclopsSetStereoMask()
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
-
context | The context for which to set the stereo mask size |
size | The new mask size, which needs to be an odd number |
- Returns
- An error code representing the outcome of the function
- Return values
-
TriclopsErrorOk | The function completed successfully |
TriclopsErrorInvalidContext | The provided context is invalid |
TriclopsErrorInvalidSetting | The provided mask size is invalid |
- See also
- triclopsGetStereoMask()
Sets a new stereo disparity range.
The maximum disparity range that can be set is currently 4078.
- Parameters
-
context | The context for which to set the new disparity range |
minDisparity | The minimum disparity to compute |
maxDisparity | How many disparities to compute |
- Returns
- An error code representing the outcome of the function
- Return values
-
TriclopsErrorOk | The function completed successfully |
TriclopsErrorInvalidContext | The provided context is invalid |
TriclopsErrorInvalidNumberDisparities | The provided number of disparities is invalid (i.e. less or equal than zero) |
TriclopsErrorInvalidSetting | The 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()
Switches stereo computation on or off.
triclopsStereo() will return TriclopsErrorOk without doing nothing if stereo computation is set to off
- Parameters
-
context | The context for which to enable/disable stereo computation |
on | Whether stereo computation should be on or off |
- Returns
- An error code representing the outcome of the function
- Return values
-
TriclopsErrorOk | The function completed successfully |
TriclopsErrorInvalidContext | The provided context is invalid |
- See also
- triclopsGetDoStereo()
Sets a new stereo algorithm.
- Parameters
-
context | The context for which to set the stereo algorithm |
algorithm | The new stereo algorithm to use |
- Returns
- An error code representing the outcome of the function
- Return values
-
TriclopsErrorOk | The function completed successfully |
TriclopsErrorInvalidContext | The provided context is invalid |
- See also
- triclopsGetStereoAlgorithm()
Sets a new stereo mask size.
- Parameters
-
context | The context for which to set the stereo mask size |
masksize | The 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
-
TriclopsErrorOk | The function completed successfully |
TriclopsErrorInvalidContext | The provided context is invalid |
TriclopsErrorInvalidSetting | The provided mask size is invalid |
- See also
- triclopsGetStereoMask()
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
-
context | The context on which to perform depth computation |
- Returns
- An error code representing the outcome of the function
- Return values
-
TriclopsErrorOk | The function completed successfully |
TriclopsErrorRectificationNotProcessed | This function has been called before calling triclopsRectify() or triclopsColorRectify() |
TriclopsErrorInvalidCameraConfig | The stereo algorithm set in the provided context is non-existant (i.e. wrong triclopsSetStereoAlgorithm() parameter) |
TriclopsErrorInvalidStereoROI | The ROI requested, combined with stereo and edge mask, is invalid (e.g. the resulting area is too small) |
TriclopsErrorUnknown | The 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()