You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Copy file name to clipboardExpand all lines: docs/source/components/nodes/stereo_depth.rst
+215Lines changed: 215 additions & 0 deletions
Original file line number
Diff line number
Diff line change
@@ -288,6 +288,221 @@ as:
288
288
For the final disparity map, a filtering is applied based on the confidence threshold value: the pixels that have their confidence score larger than
289
289
the threshold get invalidated, i.e. their disparity value is set to zero. You can set the confidence threshold with :code:`stereo.initialConfig.setConfidenceThreshold()`.
290
290
291
+
Calculate depth using disparity map
292
+
===================================
293
+
294
+
Disparity and depth are inversely related. As disparity decreases, depth increases exponentially depending on baseline and focal length. Meaning, if the disparity value is close to zero, then a small change in disparity generates a large change in depth. Similarly, if the disparity value is big, then large changes in disparity do not lead to a large change in depth.
295
+
296
+
By considering this fact, depth can be calculated using this formula:
Examples for calculating the depth value, using the OAK-D (7.5cm baseline):
329
+
330
+
.. code-block:: python
331
+
332
+
# For OAK-D @ 400P mono cameras and disparity of eg. 50 pixels
333
+
depth =441.25*7.5/50=66.19# cm
334
+
335
+
# For OAK-D @ 800P mono cameras and disparity of eg. 10 pixels
336
+
depth =882.5*7.5/10=661.88# cm
337
+
338
+
Note the value of disparity depth data is stored in :code:`uint16`, where 0 is a special value, meaning that distance is unknown.
339
+
340
+
Min stereo depth distance
341
+
=========================
342
+
343
+
If the depth results for close-in objects look weird, this is likely because they are below the minimum depth-perception distance of the device.
344
+
345
+
To calculate this minimum distance, use the :ref:`depth formula <Calculate depth using disparity map>` and choose the maximum value for disparity_in_pixels parameter (keep in mind it is inveresly related, so maximum value will yield the smallest result).
346
+
347
+
For example OAK-D has a baseline of **7.5cm**, focal_length_in_pixels of **882.5 pixels** and the default maximum value for disparity_in_pixels is **95**. By using the :ref:`depth formula <Calculate depth using disparity map>` we get:
However this distance can be cut in 1/2 (to around 35cm for the OAK-D) with the following options:
356
+
357
+
1. Changing the resolution to 640x400, instead of the standard 1280x800.
358
+
359
+
2. Enabling Extended Disparity.
360
+
361
+
Extended Disparity mode increases the levels of disparity to 191 from the standard 96 pixels, thereby 1/2-ing the minimum depth. It does so by computing the 96-pixel disparities on the original 1280x720 and on the downscaled 640x360 image, which are then merged to a 191-level disparity. For more information see the Extended Disparity tab in :ref:`this table <Currently configurable blocks>`.
362
+
363
+
Using the previous OAK-D example, disparity_in_pixels now becomes **190** and the minimum distance is:
Applying both of those options is possible, which would set the minimum depth to 1/4 of the standard settings, but at such short distances the minimum depth is limited by focal length, which is 19.6cm, since OAK-D mono cameras have fixed focus distance: 19.6cm - infinity.
374
+
375
+
See `these examples <https://github.com/luxonis/depthai-experiments/tree/master/gen2-camera-demo#real-time-depth-from-depthai-stereo-pair>`__ for how to enable Extended Disparity.
376
+
377
+
Disparity shift to lower min depth perception
378
+
---------------------------------------------
379
+
380
+
Another option to perceive closer depth range is to use disparity shift. Disparity shift will shift the starting point
381
+
of the disparity search, which will significantly decrease max depth (MazZ) perception, but it will also decrease min depth (MinZ) perception.
382
+
Disparity shift can be combined with extended/subpixel/LR-check modes.
**Left graph** shows min and max disparity and depth for OAK-D (7.5cm baseline, 800P resolution, ~70° HFOV) by default (disparity shift=0). See :ref:`Calculate depth using disparity map`.
387
+
Since hardware (stereo block) has a fixed 95 pixel disparity search, DepthAI will search from 0 pixels (depth=INF) to 95 pixels (depth=71cm).
388
+
389
+
**Right graph** shows the same, but at disparity shift set to 30 pixels. This means that disparity search will be from 30 pixels (depth=2.2m) to 125 pixels (depth=50cm).
390
+
This also means that depth will be very accurate at the short range (**theoretically** below 5mm depth error).
391
+
392
+
**Limitations**:
393
+
394
+
- Because of the inverse relationship between disparity and depth, MaxZ will decrease much faster than MinZ as the disparity shift is increased. Therefore, it is **advised not to use a larger than necessary disparity shift**.
395
+
- Tradeoff in reducing the MinZ this way is that objects at **distances farther away than MaxZ will not be seen**.
396
+
- Because of the point above, **we only recommend using disparity shift when MaxZ is known**, such as having a depth camera mounted above a table pointing down at the table surface.
397
+
- Output disparity map is not expanded, only the depth map. So if disparity shift is set to 50, and disparity value obtained is 90, the real disparity is 140.
398
+
399
+
**Compared to Extended disparity**, disparity shift:
400
+
401
+
- **(+)** Is faster, as it doesn't require an extra computation, which means there's also no extra latency
402
+
- **(-)** Reduces the MaxZ (significantly), while extended disparity only reduces MinZ.
403
+
404
+
Disparity shift can be combined with extended disparity.
The maximum depth perception distance depends on the :ref:`accuracy of the depth perception <Depth perception accuracy>`. The formula used to calculate this distance is an approximation, but is as follows:
If greater precision for long range measurements is required, consider enabling Subpixel Disparity or using a larger baseline distance between mono cameras. For a custom baseline, you could consider using `OAK-FFC <https://docs.luxonis.com/projects/hardware/en/latest/pages/DM1090.html>`__ device or design your own baseboard PCB with required baseline. For more information see Subpixel Disparity under the Stereo Mode tab in :ref:`this table <Currently configurable blocks>`.
430
+
431
+
Depth perception accuracy
432
+
=========================
433
+
434
+
Disparity depth works by matching features from one image to the other and its accuracy is based on multiple parameters:
435
+
436
+
* Texture of objects / backgrounds
437
+
438
+
Backgrounds may interfere with the object detection, since backgrounds are objects too, which will make depth perception less accurate. So disparity depth works very well outdoors as there are very rarely perfectly-clean/blank surfaces there - but these are relatively commonplace indoors (in clean buildings at least).
439
+
440
+
* Lighting
441
+
442
+
If the illumination is low, the diparity map will be of low confidence, which will result in a noisy depth map.
443
+
444
+
* Baseline / distance to objects
445
+
446
+
Lower baseline enables us to detect the depth at a closer distance as long as the object is visible in both the frames. However, this reduces the accuracy for large distances due to less pixels representing the object and disparity decreasing towards 0 much faster.
447
+
So the common norm is to adjust the baseline according to how far/close we want to be able to detect objects.
448
+
449
+
Limitation
450
+
==========
451
+
452
+
Since depth is calculated from disparity, which requires the pixels to overlap, there is inherently a vertical
453
+
band on the left side of the left mono camera and on the right side of the right mono camera, where depth
454
+
cannot be calculated, since it is seen by only 1 camera. That band is marked with :code:`B`
0 commit comments