Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
32 changes: 32 additions & 0 deletions docs/source/components/messages/stereo_depth_config.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
StereoDepthConfig
=================

This message is used to configure the :ref:`StereoDepth` node.
With this message you can set filters, confidences, thresholds and mode of the :ref:`StereoDepth` node.

Examples of functionality
#########################

- :ref:`Stereo Depth from host`

Reference
#########

.. tabs::

.. tab:: Python

.. autoclass:: depthai.StereoDepthConfig
:members:
:inherited-members:
:noindex:

.. tab:: C++

.. doxygenclass:: dai::StereoDepthConfig
:project: depthai-core
:members:
:private-members:
:undoc-members:

.. include:: ../../includes/footer-short.rst
71 changes: 45 additions & 26 deletions docs/source/components/nodes/stereo_depth.rst
Original file line number Diff line number Diff line change
Expand Up @@ -25,30 +25,50 @@ Inputs and Outputs
.. code-block::

┌───────────────────┐
│ │ confidenceMap
│ ├─────────────►
│ │rectifiedLeft
│ ├─────────────►
left │ │ syncedLeft
──────────────►│ ├─────────────►
──────────────►│-------------------├─────────────►
│ │ depth
│ ├─────────────►
│ StereoDepth │ disparity
│ ├─────────────►
right │ │rectifiedRight
──────────────►│ ├─────────────►
│ │ syncedRight
right │ │ syncedRight
──────────────►│-------------------├─────────────►
│ │rectifiedRight
│ ├─────────────►
inputConfig │ | outConfig
──────────────►│-------------------├─────────────►
└───────────────────┘

**Message types**
.. tabs::

.. tab:: **Inputs**

- :code:`left` - :ref:`ImgFrame` from the left :ref:`MonoCamera`
- :code:`right` - :ref:`ImgFrame` from the right :ref:`MonoCamera`
- :code:`inputConfig` - :ref:`StereoDepthConfig`

.. tab:: **Outputs**

- :code:`confidenceMap` - :ref:`ImgFrame`
- :code:`rectifiedLeft` - :ref:`ImgFrame`
- :code:`syncedLeft` - :ref:`ImgFrame`
- :code:`depth` - :ref:`ImgFrame`
- :code:`disparity` - :ref:`ImgFrame`
- :code:`rectifiedRight` - :ref:`ImgFrame`
- :code:`syncedRight` - :ref:`ImgFrame`
- :code:`outConfig` - :ref:`StereoDepthConfig`

- :code:`left` - :ref:`ImgFrame` from the left :ref:`MonoCamera`
- :code:`right` - :ref:`ImgFrame` from the right :ref:`MonoCamera`
- :code:`rectifiedLeft` - :ref:`ImgFrame`
- :code:`syncedLeft` - :ref:`ImgFrame`
- :code:`depth` - :ref:`ImgFrame`
- :code:`disparity` - :ref:`ImgFrame`
- :code:`rectifiedRight` - :ref:`ImgFrame`
- :code:`syncedRight` - :ref:`ImgFrame`
.. tab:: **Debug outputs**

- :code:`debugDispLrCheckIt1` - :ref:`ImgFrame`
- :code:`debugDispLrCheckIt2` - :ref:`ImgFrame`
- :code:`debugExtDispLrCheckIt1` - :ref:`ImgFrame`
- :code:`debugExtDispLrCheckIt2` - :ref:`ImgFrame`
- :code:`debugDispCostDump` - :ref:`ImgFrame`

Internal block diagram of StereoDepth node
##########################################
Expand All @@ -73,32 +93,36 @@ Currently configurable blocks

.. tab:: Left-Right Check

Left-Right Check or LR-Check is used to remove incorrectly calculated disparity pixels due to occlusions at object borders (Left and Right camera views
**Left-Right Check** or LR-Check is used to remove incorrectly calculated disparity pixels due to occlusions at object borders (Left and Right camera views
are slightly different).

#. Computes disparity by matching in R->L direction
#. Computes disparity by matching in L->R direction
#. Combines results from 1 and 2, running on Shave: each pixel d = disparity_LR(x,y) is compared with disparity_RL(x-d,y). If the difference is above a threshold, the pixel at (x,y) in the final disparity map is invalidated.

You can use :code:`debugDispLrCheckIt1` and :code:`debugDispLrCheckIt2` debug outputs for debugging/fine-tuning purposes.

.. tab:: Extended Disparity

The :code:`extended disparity` allows detecting closer distance objects for the given baseline. This increases the maximum disparity search from 96 to 191, meaning the range is now: **[0..190]**.
**Extended disparity mode** allows detecting closer distance objects for the given baseline. This increases the maximum disparity search from 96 to 191, meaning the range is now: **[0..190]**.
So this cuts the minimum perceivable distance in half, given that the minimum distance is now :code:`focal_length * base_line_dist / 190` instead
of :code:`focal_length * base_line_dist / 95`.

#. Computes disparity on the original size images (e.g. 1280x720)
#. Computes disparity on 2x downscaled images (e.g. 640x360)
#. Combines the two level disparities on Shave, effectively covering a total disparity range of 191 pixels (in relation to the original resolution).

You can use :code:`debugExtDispLrCheckIt1` and :code:`debugExtDispLrCheckIt2` debug outputs for debugging/fine-tuning purposes.

.. tab:: Subpixel Disparity

Subpixel improves the precision and is especially useful for long range measurements. It also helps for better estimating surface normals.
**Subpixel mode** improves the precision and is especially useful for long range measurements. It also helps for better estimating surface normals.

Besides the integer disparity output, the Stereo engine is programmed to dump to memory the cost volume, that is 96 levels (disparities) per pixel,
then software interpolation is done on Shave, resulting a final disparity with 5 fractional bits, resulting in significantly more granular depth
steps (32 additional steps between the integer-pixel depth steps), and also theoretically, longer-distance depth viewing - as the maximum depth
is no longer limited by a feature being a full integer pixel-step apart, but rather 1/32 of a pixel. In this mode, stereo cameras perform: :code:`96 depth steps * 32 subpixel depth steps = 3,072 depth steps.`
Note that Subpixel and Extended Disparity are not yet supported simultaneously (which would result in :code:`191 * 32 = 6,112 depth steps`), but should be available in the near future (`Pull Request <https://github.com/luxonis/depthai-python/pull/347>`__).
then software interpolation is done on Shave, resulting a final disparity with 3 fractional bits, resulting in significantly more granular depth
steps (8 additional steps between the integer-pixel depth steps), and also theoretically, longer-distance depth viewing - as the maximum depth
is no longer limited by a feature being a full integer pixel-step apart, but rather 1/8 of a pixel. In this mode, stereo cameras perform: :code:`94 depth steps * 8 subpixel depth steps + 2 (min/max values) = 754 depth steps`
Note that Subpixel and Extended Disparity are not yet supported simultaneously.

For comparison of normal disparity vs. subpixel disparity images, click `here <https://github.com/luxonis/depthai/issues/184>`__.

Expand Down Expand Up @@ -138,12 +162,7 @@ Currently configurable blocks
Current limitations
###################

If one or more of the additional depth modes (:code:`lrcheck`, :code:`extended`, :code:`subpixel`) are enabled, then:

- median filtering is disabled on device
- with subpixel, if both :code:`depth` and :code:`disparity` are used, only :code:`depth` will have valid output

Otherwise, :code:`depth` output is **U16** (in millimeters) and median is functional.
- Median filtering is disabled when subpixel mode is set to 4 or 5 bits.

Stereo depth FPS
################
Expand Down