DepthAI Tutorials
DepthAI API References

ON THIS PAGE

  • Depth Post-Processing
  • Demo
  • Depth filters
  • Similar samples:
  • Setup
  • Source code
  • Pipeline

Depth Post-Processing

This example shows how you can run depth post-processing filters on the device itself to reduce noise, smooth the depth map and overall improve the depth map quality. Post-processing can be added to StereoDepth node.

Demo

Depth filters

Median

This is a non-edge preserving Median filter, which can be used to reduce noise and smoothen the depth map. Median filter is implemented in hardware, so it's the fastest filter.

Speckle

Speckle Filter is used to reduce the speckle noise. Speckle noise is a region with huge variance between neighboring disparity/depth pixels, and speckle filter tries to filter this region.
class

depthai.StereoDepthConfig.PostProcessing.SpeckleFilter

Temporal

Temporal Filter is intended to improve the depth data persistency by manipulating per-pixel values based on previous frames. The filter performs a single pass on the data, adjusting the depth values while also updating the tracking history. In cases where the pixel data is missing or invalid, the filter uses a user-defined persistency mode to decide whether the missing value should be rectified with stored data. Note that due to its reliance on historic data, the filter may introduce visible blurring/smearing artifacts, and therefore is best-suited for static scenes.
class

depthai.StereoDepthConfig.PostProcessing.TemporalFilter

class
PersistencyMode
Persistency algorithm type.  Members:    PERSISTENCY_OFF :     VALID_8_OUT_OF_8 :     VALID_2_IN_LAST_3 :     VALID_2_IN_LAST_4 :     VALID_2_OUT_OF_8 :     VALID_1_IN_LAST_2 :     VALID_1_IN_LAST_5 :     VALID_1_IN_LAST_8 :     PERSISTENCY_INDEFINITELY : 
method
property
alpha
The Alpha factor in an exponential moving average with Alpha=1 - no filter. Alpha = 0 - infinite filter. Determines the extent of the temporal history that should be averaged.
method
property
delta
Step-size boundary. Establishes the threshold used to preserve surfaces (edges). If the disparity value between neighboring pixels exceed the disparity threshold set by this delta parameter, then filtering will be temporarily disabled. Default value 0 means auto: 3 disparity integer levels. In case of subpixel mode it's 3*number of subpixel levels.
method
property
enable
Whether to enable or disable the filter.
method
property
persistencyMode
Persistency mode. If the current disparity/depth value is invalid, it will be replaced by an older value, based on persistency mode.
method
class

depthai.StereoDepthConfig.PostProcessing.TemporalFilter.PersistencyMode

variable
variable
variable
variable
variable
variable
variable
variable
variable
variable
method
method
method
method
method
method
method
method
method
method
property
property

Spatial

Spatial Edge-Preserving Filter will fill invalid depth pixels with valid neighboring depth pixels. It performs a series of 1D horizontal and vertical passes or iterations, to enhance the smoothness of the reconstructed data. It is based on this research paper.
class

depthai.StereoDepthConfig.PostProcessing.SpatialFilter

method
property
alpha
The Alpha factor in an exponential moving average with Alpha=1 - no filter. Alpha = 0 - infinite filter. Determines the amount of smoothing.
method
property
delta
Step-size boundary. Establishes the threshold used to preserve "edges". If the disparity value between neighboring pixels exceed the disparity threshold set by this delta parameter, then filtering will be temporarily disabled. Default value 0 means auto: 3 disparity integer levels. In case of subpixel mode it's 3*number of subpixel levels.
method
property
enable
Whether to enable or disable the filter.
method
property
holeFillingRadius
An in-place heuristic symmetric hole-filling mode applied horizontally during the filter passes. Intended to rectify minor artefacts with minimal performance impact. Search radius for hole filling.
method
property
numIterations
Number of iterations over the image in both horizontal and vertical direction.
method

Threshold

Threshold Filter filters out all disparity/depth pixels outside the configured min/max threshold values.
Python
1class ThresholdFilter:
2'''
3    Spatial Edge-Preserving Filter will fill invalid depth pixels with valid neighboring depth pixels.
4    It performs a series of 1D horizontal and vertical passes or iterations, to enhance the smoothness of the reconstructed data. It is based on [this research paper](https://www.inf.ufrgs.br/~eslgastal/DomainTransform/).
5'''

Similar samples:

Setup

Please run the install script to download all required dependencies. Please note that this script must be ran from git context, so you have to download the depthai-python repository first and then run the script
Command Line
1git clone https://github.com/luxonis/depthai-python.git
2cd depthai-python/examples
3python3 install_requirements.py
For additional information, please follow the installation guide.

Source code

Python
C++

Python

Python
GitHub
1#!/usr/bin/env python3
2
3import cv2
4import depthai as dai
5import numpy as np
6
7# Closer-in minimum depth, disparity range is doubled (from 95 to 190):
8extended_disparity = False
9# Better accuracy for longer distance, fractional disparity 32-levels:
10subpixel = False
11# Better handling for occlusions:
12lr_check = True
13
14# Create pipeline
15pipeline = dai.Pipeline()
16
17# Define sources and outputs
18monoLeft = pipeline.create(dai.node.MonoCamera)
19monoRight = pipeline.create(dai.node.MonoCamera)
20depth = pipeline.create(dai.node.StereoDepth)
21xout = pipeline.create(dai.node.XLinkOut)
22
23xout.setStreamName("disparity")
24
25# Properties
26monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P)
27monoLeft.setCamera("left")
28monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P)
29monoRight.setCamera("right")
30
31# Create a node that will produce the depth map (using disparity output as it's easier to visualize depth this way)
32depth.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_DENSITY)
33# Options: MEDIAN_OFF, KERNEL_3x3, KERNEL_5x5, KERNEL_7x7 (default)
34depth.initialConfig.setMedianFilter(dai.MedianFilter.KERNEL_7x7)
35depth.setLeftRightCheck(lr_check)
36depth.setExtendedDisparity(extended_disparity)
37depth.setSubpixel(subpixel)
38
39config = depth.initialConfig.get()
40config.postProcessing.speckleFilter.enable = False
41config.postProcessing.speckleFilter.speckleRange = 50
42config.postProcessing.temporalFilter.enable = True
43config.postProcessing.spatialFilter.enable = True
44config.postProcessing.spatialFilter.holeFillingRadius = 2
45config.postProcessing.spatialFilter.numIterations = 1
46config.postProcessing.thresholdFilter.minRange = 400
47config.postProcessing.thresholdFilter.maxRange = 15000
48config.postProcessing.decimationFilter.decimationFactor = 1
49depth.initialConfig.set(config)
50
51# Linking
52monoLeft.out.link(depth.left)
53monoRight.out.link(depth.right)
54depth.disparity.link(xout.input)
55
56# Connect to device and start pipeline
57with dai.Device(pipeline) as device:
58
59    # Output queue will be used to get the disparity frames from the outputs defined above
60    q = device.getOutputQueue(name="disparity", maxSize=4, blocking=False)
61
62    while True:
63        inDisparity = q.get()  # blocking call, will wait until a new data has arrived
64        frame = inDisparity.getFrame()
65        # Normalization for better visualization
66        frame = (frame * (255 / depth.initialConfig.getMaxDisparity())).astype(np.uint8)
67
68        cv2.imshow("disparity", frame)
69
70        # Available color maps: https://docs.opencv.org/3.4/d3/d50/group__imgproc__colormap.html
71        frame = cv2.applyColorMap(frame, cv2.COLORMAP_JET)
72        cv2.imshow("disparity_color", frame)
73
74        if cv2.waitKey(1) == ord('q'):
75            break

Pipeline

Need assistance?

Head over to Discussion Forum for technical support or any other questions you might have.