# StereoDepth

StereoDepth node calculates disparity and/or depth from a stereo pair of
[Camera](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/camera.md) nodes.

### Configure Stereo Depth

Learn how to achieve the best depth results with step-by-step configuration guide.

[Open tutorial](https://docs.luxonis.com/hardware/platform/depth/configuring-stereo-depth.md)

To view the accuracy measurements, see [Depth Accuracy](https://docs.luxonis.com/hardware/platform/depth/depth-accuracy.md).

## How to place it

#### Python

```python
pipeline = dai.Pipeline()
stereo = pipeline.create(dai.node.StereoDepth)
```

#### C++

```cpp
dai::Pipeline pipeline;
auto stereo = pipeline.create<dai::node::StereoDepth>();
```

## Inputs and Outputs

 * Debug outputs:
   * debugDispLrCheckIt1: [ImgFrame](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/img_frame.md)
   * debugDispLrCheckIt2: [ImgFrame](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/img_frame.md)
   * debugExtDispLrCheckIt1: [ImgFrame](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/img_frame.md)
   * debugExtDispLrCheckIt2: [ImgFrame](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/img_frame.md)
   * debugDispCostDump: [ImgFrame](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/img_frame.md)
   * confidenceMap: [ImgFrame](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/img_frame.md)

## Usage

#### Python

```python
pipeline = dai.Pipeline()
stereo = pipeline.create(dai.node.StereoDepth)

# Set profile preset to ROBOTICS
stereo.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.ROBOTICS)
# Better handling for occlusions:
stereo.setLeftRightCheck(True)
# Closer-in minimum depth, disparity range is doubled:
stereo.setExtendedDisparity(True)
# Better accuracy for longer distance, fractional disparity 32-levels:
stereo.setSubpixel(True)

# Define and configure MonoCamera nodes beforehand
left.out.link(stereo.left)
right.out.link(stereo.right)
```

#### C++

```cpp
dai::Pipeline pipeline;
auto stereo = pipeline.create<dai::node::StereoDepth>();

// Set profile preset to ROBOTICS
stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::ROBOTICS);
// Better handling for occlusions:
stereo->setLeftRightCheck(true);
// Closer-in minimum depth, disparity range is doubled:
stereo->setExtendedDisparity(true);
// Better accuracy for longer distance, fractional disparity 32-levels:
stereo->setSubpixel(true);

// Define and configure MonoCamera nodes beforehand
left->out.link(stereo->left);
right->out.link(stereo->right);
```

## Examples of functionality

 * [Stereo Depth](https://docs.luxonis.com/software-v3/depthai/examples/stereo_depth/stereo_depth.md) - Visualize disparity depth
   from stereo camera.
 * [Stereo Depth Remap](https://docs.luxonis.com/software-v3/depthai/examples/stereo_depth/stereo_depth_remap.md) - Remap geometry
   from disparity depth <frame> to color frame.
 * [Stereo Depth From Host](https://docs.luxonis.com/software-v3/depthai/examples/stereo_depth/stereo_depth_from_host.md) - Runs
   stereo disparity on-device using pre-rectified stereo images from the host.
 * [Stereo Depth Filters](https://docs.luxonis.com/software-v3/depthai/examples/stereo_depth/stereo_depth_filters.md) - Apply
   various filters to the stereo depth output.
 * [Stereo Depth Calibration
   Update](https://docs.luxonis.com/software-v3/depthai/examples/stereo_depth/stereo_depth_calibration_update.md) - Update stereo
   calibration parameters on-the-fly.

## Depth Alignment

Image alignment is used for aligning depth map to a specific stream.

For Depthai v3, the default Stereo Depth alignment is RECTIFIED_LEFT.

```python
pipeline = dai.Pipeline()
stereo = pipeline.create(dai.node.StereoDepth)
 # alignment to RECTIFIED_LEFT or RECTIFIED_RIGHT
stereo.setDepthAlign(dai.StereoDepthConfig.AlgorithmControl.DepthAlign.RECTIFIED_LEFT)
```

Or you can use the [ImageAlign](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/image_align.md) node:

```python
align = pipeline.create(dai.node.ImageAlign)
stereo.depth.link(align.input)
rgbOut.link(align.inputAlignTo)  # Align depth to RGB
align.outputAligned.link(sync.inputs["depth_aligned"])
```

## Configure Camera for High FPS

The performance of the Stereo node is directly constrained by the MonoCamera configuration. To achieve high frame rates (e.g., 60
FPS) with StereoDepth, the MonoCameras must be configured to deliver frames at the required rate.

```python
with dai.Pipeline(device) as pipeline:
  stereo = pipeline.create(dai.node.StereoDepth)
  mono_left = pipeline.create(dai.node.Camera).build(dai.CameraBoardSocket.CAM_B)
  mono_right = pipeline.create(dai.node.Camera).build(dai.CameraBoardSocket.CAM_C)

  def configure_cam(cam, size_x: int, size_y: int, fps: float):
    cap = dai.ImgFrameCapability()
    cap.size.fixed((size_x, size_y))
    cap.fps.fixed(fps)
  return cam.requestOutput(cap, True)

  # Configure MonoCameras for 60 FPS at 640x400
  mono_left_out = configure_cam(mono_left, 640, 400, 60)
  mono_right_out = configure_cam(mono_right, 640, 400, 60)
```

From a processing standpoint, and in the absence of MonoCamera input constraints, the Stereo node itself is capable of processing
image pairs at rates of up to 400 FPS when operating on 256×256 pixel inputs. By default, however, the MonoCameras operate at 30
FPS, which limits the overall StereoDepth output accordingly.

## Changing camera calibration during runtime

Changing the camera calibration during runtime is possible. The calibration can be changed using the device.setCalibration()
method and can be used in combination with [dynamic
calibration](https://docs.luxonis.com/hardware/platform/depth/dynamic-calibration.md) if device stereo quality degrades over time
due to environmental factors. The same data can be obtained using the device.getCalibration().

## Platform-Specific Configuration

Select your platform (RVC2 or RVC4) to view platform-specific documentation, presets, configuration options, and limitations.

#### RVC2

## Internal block diagram of StereoDepth node

## Depth Presets

We have made a few depth presets that can be used to quickly set up the StereoDepth node for different scenarios, without having
to manually set all the parameters. For detailed preset specifications including all parameter values, see [Configuring stereo
depth](https://docs.luxonis.com/hardware/platform/depth/configuring-stereo-depth.md).

| Stereo depth preset | Use case | FPS @800P | FPS @400P | Output resolution | Motion Blur | Range (meters) |
| --- | --- | --- | --- | --- | --- | --- |
| Default | General purpose | 16 | 30 | 1/2 Input Resolution | True | 0–10 |
| Face | Face tracking, biometrics | 16 | 30 | 1/2 Input Resolution | True | 0–3 |
| High Detail | 3D scanning, object details | 16 | 30 | 1/2 Input Resolution | True | 0–15 |
| Robotics | Navigation, obstacle detection | 16 | 34 | 1/2 Input Resolution | False | 0–15 |
| Fast Accuracy | General purpose | 30 | 90 | Input Resolution | False | 0–65 |
| Fast Density | General purpose | 30 | 90 | Input Resolution | False | 0–65 |
| Fast Density No Subpixel | General purpose | 50 | 110 | Input Resolution | False | 0–65 |

Output resolution can get reduced by half due to the use of decimation filter, meaning that if the input resolution is 1280x800
(800P), it would get reduced to 640x400 (400P). For some Depth Presets, the output resolution can be different due to the use of
decimation filter. By default, all profile presets have subpixel ON, this produces much finer depth details but leads to lower
FPS. For high FPS, turn subpixel OFF. Profile Presets High Detail and Face have by default Extended disparity ON.

## Depth Configuration

### Extended Disparity

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].

 1. Computes disparity on the original size images (e.g. 1280x720).
 2. Computes disparity on 2x downscaled images (e.g. 640x360).
 3. 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 debugExtDispLrCheckIt1 and debugExtDispLrCheckIt2 debug outputs for debugging/fine-tuning purposes.

#### Usage:

```python
stereo.setExtendedDisparity(True)
```

Note: On RVC2, companding (costMatching.enableCompanding) is an alternative to Extended Disparity: with companding the stereo
block uses sparse matching so the disparity range extends to 176 values, meaning the range is [0..175]. Matching is dense
(pixel-by-pixel) for the first part of the range and progressively sparser (every 2nd, then every 4th pixel) for higher
disparities, and only the depth output uses this extended range—the disparity map itself stays in the normal range.

### Subpixel Disparity

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

In this mode, stereo cameras perform: 94 depth steps * 8 subpixel depth steps + 2 (min/max values) = 754 depth steps.

The number of unique depth values depends on the subpixel fractional bits setting:

| Subpixel Fractional Bits | Number of Unique Values |
| --- | --- |
| 3 | 754 |
| 4 | 1506 |
| 5 | 3010 |

#### Usage:

```python
stereo.setSubpixel(True)
stereo.initialConfig.setSubpixelFractionalBits(3)  # 3, 4 or 5
```

### LR 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 are slightly different).

 1. Computes disparity by matching in R->L direction.
 2. Computes disparity by matching in L->R direction.
 3. Combines results from steps 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 debugDispLrCheckIt1 and debugDispLrCheckIt2 debug outputs for debugging/fine-tuning purposes.

LR check threshold: Disparity is considered for the output when the difference between LR and RL disparities is smaller than the
LR check threshold.

#### Usage:

```python
stereo.setLeftRightCheck(True)
stereo.initialConfig.setLeftRightCheckThreshold(4)  # Set threshold value
```

### Confidence Threshold

Confidence threshold: Stereo depth algorithm searches for the matching feature from the right camera point to the left image
(along the 96 disparity levels). During this process, it computes the cost for each disparity level and chooses the minimal cost
between two disparities and uses it to compute the confidence at each pixel. Stereo node will output disparity/depth pixels only
where depth confidence is below the confidence threshold (lower the confidence value means better depth accuracy).

The confidence score is inverted:

 * 0 - maximum confidence that it holds a valid value
 * 255 - minimum confidence, so there is more chance that the value is incorrect

#### Usage:

```python
stereo.initialConfig.setConfidenceThreshold(200)  # Lower value = better accuracy, less fill rate
```

### Median Filter

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.

Note: Median filtering is disabled when subpixel mode is set to 4 or 5 bits.

#### Usage:

```python
stereo.initialConfig.setMedianFilter(dai.MedianFilter.KERNEL_7x7)  # Options: MEDIAN_OFF, KERNEL_3x3, KERNEL_5x5, KERNEL_7x7
```

### Speckle Filter

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.

#### Usage:

```python
stereo.initialConfig.postProcessing.speckleFilter.enable = True
stereo.initialConfig.postProcessing.speckleFilter.speckleRange = 48
```

### Temporal Filter

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 improved with stored data. Note that due to its reliance on historic data, the filter may introduce visible motion
blurring/smearing artifacts, and therefore is best-suited for static scenes.

#### Usage:

```python
stereo.initialConfig.postProcessing.temporalFilter.enable = True
stereo.initialConfig.postProcessing.temporalFilter.alpha = 0.4  # Weight of current frame (0-1)
stereo.initialConfig.postProcessing.temporalFilter.delta = 3  # Threshold for valid depth change
```

### Spatial Filter

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](https://www.inf.ufrgs.br/~eslgastal/DomainTransform/).

#### Usage:

```python
stereo.initialConfig.postProcessing.spatialFilter.enable = True
stereo.initialConfig.postProcessing.spatialFilter.alpha = 0.5  # Edge-preserving strength
stereo.initialConfig.postProcessing.spatialFilter.delta = 8  # Threshold for valid depth change
stereo.initialConfig.postProcessing.spatialFilter.holeFillingRadius = 2  # Radius for hole filling
stereo.initialConfig.postProcessing.spatialFilter.numIterations = 1  # Number of iterations
```

### Brightness Filter

Brightness filter will filter out (invalidate, by setting to 0) all depth pixels for which input stereo camera image pixels are
outside the configured min/max brightness threshold values. This filter is useful when you have a high dynamic range scene, like
outside on a bright day, or in general whenever stereo camera pair can directly see a light source.

It also helps with rectification "artifacts", especially when you have Wide FOV lenses and you apply alpha param.

#### Usage:

```python
stereo.initialConfig.postProcessing.brightnessFilter.enable = True
stereo.initialConfig.postProcessing.brightnessFilter.minBrightness = 0  # Minimum brightness threshold
stereo.initialConfig.postProcessing.brightnessFilter.maxBrightness = 255  # Maximum brightness threshold
```

### Threshold Filter

Threshold filter will filter out all depth pixels outside the configured min/max threshold values. In a controlled environment,
where you know exactly how far the scene can be (eg. 30cm - 2m) it's advised to use this filter.

#### Usage:

```python
stereo.initialConfig.postProcessing.thresholdFilter.minRange = 0  # Minimum depth in cm
stereo.initialConfig.postProcessing.thresholdFilter.maxRange = 200  # Maximum depth in cm
```

#### Decimation Filter

Decimation Filter will sub-sample the depth map, which means it reduces the depth scene complexity and allows other filters to run
faster. Setting decimationFactor to 2 will downscale 1280x800 depth map to 640x400. We can either select pixel skipping, median,
or mean decimation mode, and the latter two modes help with filtering as well. decimationFactor 1 disables the filter.

#### Usage:

```python
stereo.initialConfig.postProcessing.decimationFilter.decimationFactor = 2  # 1 = disabled, 2 = 2x downscale, etc.
```

### Filtering Order

The order of the filters is important, as the output of one filter is the input of the next filter. The order of the filters is
customizable:

Usage:

```python
config.postProcessing.filteringOrder = [
    dai.RawStereoDepthConfig.PostProcessing.Filter.TEMPORAL,
    dai.RawStereoDepthConfig.PostProcessing.Filter.SPECKLE,
    dai.RawStereoDepthConfig.PostProcessing.Filter.SPATIAL,
    dai.RawStereoDepthConfig.PostProcessing.Filter.MEDIAN,
    dai.RawStereoDepthConfig.PostProcessing.Filter.DECIMATION
]
stereo.initialConfig.set(config)
```

## Limitations

 * Median filtering is disabled when subpixel mode is set to 4 or 5 bits.
 * For RGB-depth alignment the RGB camera has to be placed on the same horizontal line as the stereo camera pair.
 * RGB-depth alignment doesn't work when using disparity shift.

#### RVC4

## Internal block diagram of StereoDepth node

## Depth Presets

We have made a few depth presets that can be used to quickly set up the StereoDepth node for different scenarios, without having
to manually set all the parameters. For detailed preset specifications including all parameter values, see [Configuring stereo
depth](https://docs.luxonis.com/hardware/platform/depth/configuring-stereo-depth.md).

| Stereo depth preset | Use case | FPS @800P | FPS @400P | Output resolution | Motion Blur | Range (meters) |
| --- | --- | --- | --- | --- | --- | --- |
| Fast Accuracy | General purpose | 60 | 60 | Input Resolution | False | 0–65 |
| Fast Density | General purpose | 36 | 60 | Input Resolution | False | 0–65 |

> These speeds will be increased in future versions of DepthAI — up to 72 FPS for Fast Density and 120 FPS for Fast Accuracy.

## Depth Configuration

### Extended Disparity

Extended disparity mode allows detecting closer/nearer objects for the given baseline. This increases the maximum disparity search
from 64 to 128, meaning the range is now: [0..127].

 1. Computes disparity on the original size images (e.g. 1280x800).
 2. Computes disparity on 2x downscaled images (e.g. 640x400).
 3. Combines the two level disparities.

#### Usage:

```python
stereo.setExtendedDisparity(True)
```

### Subpixel Disparity

Subpixel mode improves disparity precision and is especially useful for long-range depth measurements. It also enables more
accurate estimation of surface normals.

On RVC4, subpixel processing is enabled by default and cannot be disabled, as it is fixed in hardware. The implementation uses 4
fractional bits.

### LR 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 are slightly different).

On RVC4, LR Check runs purely in software on CPU.

Left Right Check Threshold: Maximum allowed disparity difference between pixels. Smaller values lead to sparser depth (more pixels
invalidated).

#### Usage:

```python
stereo.initialConfig.algorithmControl.enableSwLeftRightCheck = True
stereo.initialConfig.algorithmControl.leftRightCheckThreshold = 10  # Set threshold value
```

Note: RVC4 has a different inner mechanism that basically performs the LR check functionality - this is the Occlusion Confidence
Weight (see the Confidence Metrics section below). The occlusion confidence weight compares the difference in disparity from doing
left to right and right to left search, which is essentially what LR check does.

### Software Confidence

Software Confidence filter takes disparity and confidence map (per-pixel 8‑bit confidence from the stereo hardware block) and
applies a threshold value to filter out low-confidence pixels. This filtration is done on CPU and is applied after the hardware
block generates the disparity. This filtering is performed on the CPU and is applied after the hardware block generates the
disparity. When left–right (LR) check is enabled, both L→R and R→L disparities (with their corresponding confidence maps) are
invalidated using the same threshold.

Values:

 * Limited filtration: 50-100
 * Medium filtration: 200
 * Heavy filtration: >200 (very scene specific)

#### Usage:

```python
stereo.initialConfig.costMatching.enableSwConfidenceThresholding = True
stereo.initialConfig.costMatching.confidenceThreshold = 200  # Adjust based on desired filtration level
```

### Confidence Metrics (Occlusion, Motion Vector, Flatness)

Three different metrics are used to calculate confidence maps, which get added together into one final confidence map.

 * Occlusion Confidence Weight
   
   * Basically performs LR check. Compares the difference in disparity from doing left to right and right to left search
     (forward/backward motion vector consistency).

 * Motion Vector (MV) Confidence Weight
   
   * MV Variance calculates variance in a local edge-aware window around each pixel; given a constraint to ensure depth is smooth
     and consistent within the same object.
   * MV Confidence Threshold: The threshold offset for MV variance. Valid range [0,3]. Value = 0 allows most variance.

 * Flatness Confidence Weight
   
   * Flatness considers the input image texture and masks out low texture regions with too similar neighboring features. The
     minimum amount of texture required can be adjusted with the flatness threshold.
   * Flatness Threshold: The threshold value for flat region check. The higher the value, the more likely the pixel is to be
     detected as flat region based on census feature comparison. Used for low texture regions which do not have adequate features
     for matching.
   * Flatness Override: If pixel is detected as flat, set confidence to zero.

#### Usage:

```python
# Confidence metrics weights (must sum to 32 for RVC4)
stereo.initialConfig.confidenceMetrics.occlusionConfidenceWeight = 12
stereo.initialConfig.confidenceMetrics.motionVectorConfidenceWeight = 10
stereo.initialConfig.confidenceMetrics.flatnessConfidenceWeight = 10

# Thresholds
stereo.initialConfig.confidenceMetrics.motionVectorConfidenceThreshold = 1  # Valid range [0,3]
stereo.initialConfig.confidenceMetrics.flatnessConfidenceThreshold = 5
stereo.initialConfig.confidenceMetrics.flatnessOverride = True  # Set confidence to zero if flat
```

Note: Confidence metrics weights must sum to 32 for RVC4.

### Adaptive Median Filter

Adaptive median filter applies the filter only to low-confidence pixels below a specified threshold value.

Adaptive median filter threshold: Applies filter only to low-confidence pixels below this value. This threshold should be less
than Fill confidence threshold in Hole filling.

#### Usage:

```python
stereo.initialConfig.postProcessing.adaptiveMedianFilter.enable = True
stereo.initialConfig.postProcessing.adaptiveMedianFilter.confidenceThreshold = 200  # Should be < hole filling fillConfidenceThreshold
```

### Hole Filling

Hole Filling is a post-processing filter that fills gaps in the depth map by grouping pixels into superpixels (hexagonal regions)
and computing disparity values based on high-confidence pixels within those regions. This filter modifies the confidence map to
mark filled regions.

The filter works by:

 1. Grouping pixels into superpixels (hexagonal regions)
 2. Using pixels with confidence above the high confidence threshold to calculate disparity values per superpixel
 3. Filling holes based on the fill confidence threshold and minimum valid disparity requirements

Parameters:

 * High confidence threshold - Pixels with confidence above this threshold are used to calculate disparity value per superpixel.
   If set to maximum value (255), no superpixels should be formed.
 * Fill confidence threshold - Pixels with confidence below this value are filtered out (if invalidateDisparities is set to True)
   or become part of the superpixel calculation.
 * Min valid disparity - Decides what proportion of pixels in a region need to have confidence above the high confidence threshold
   to be included in computing the disparity for the superpixel. Values: 1 (50%), 2 (25%), or 3 (12.5%). Higher min valid
   disparity leads to bigger superpixels (more hexagons).
 * Invalidate disparities - If set to True, pixels below the fill confidence threshold are filtered out from the final disparity
   map.

#### Usage:

```python
stereo.initialConfig.postProcessing.holeFilling.enable = True
stereo.initialConfig.postProcessing.holeFilling.highConfidenceThreshold = 200
stereo.initialConfig.postProcessing.holeFilling.fillConfidenceThreshold = 210
stereo.initialConfig.postProcessing.holeFilling.minValidDisparity = 1  # 1, 2, or 3
stereo.initialConfig.postProcessing.holeFilling.invalidateDisparities = True
```

### Median Filter

This is a non-edge preserving Median filter, which can be used to reduce noise and smoothen the depth map.

On RVC4: Median filter is implemented in software (CPU), and only supports 3x3 or 5x5 kernel sizes. If 7x7 is requested, it is
automatically downgraded to 5x5.

#### Usage:

```python
stereo.initialConfig.setMedianFilter(dai.MedianFilter.KERNEL_3x3)  # Options: MEDIAN_OFF, KERNEL_3x3, KERNEL_5x5
```

### Speckle Filter

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.

#### Usage:

```python
stereo.initialConfig.postProcessing.speckleFilter.enable = True
stereo.initialConfig.postProcessing.speckleFilter.speckleRange = 48
```

### Temporal Filter

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 improved with stored data. Note that due to its reliance on historic data, the filter may introduce visible motion
blurring/smearing artifacts, and therefore is best-suited for static scenes.

#### Usage:

```python
stereo.initialConfig.postProcessing.temporalFilter.enable = True
stereo.initialConfig.postProcessing.temporalFilter.alpha = 0.4  # Weight of current frame (0-1)
stereo.initialConfig.postProcessing.temporalFilter.delta = 3  # Threshold for valid depth change
```

### Spatial Filter

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](https://www.inf.ufrgs.br/~eslgastal/DomainTransform/).

#### Usage:

```python
stereo.initialConfig.postProcessing.spatialFilter.enable = True
stereo.initialConfig.postProcessing.spatialFilter.alpha = 0.5  # Edge-preserving strength
stereo.initialConfig.postProcessing.spatialFilter.delta = 8  # Threshold for valid depth change
stereo.initialConfig.postProcessing.spatialFilter.holeFillingRadius = 2  # Radius for hole filling
stereo.initialConfig.postProcessing.spatialFilter.numIterations = 1  # Number of iterations
```

### Brightness Filter

Brightness filter will filter out (invalidate, by setting to 0) all depth pixels for which input stereo camera image pixels are
outside the configured min/max brightness threshold values. This filter is useful when you have a high dynamic range scene, like
outside on a bright day, or in general whenever stereo camera pair can directly see a light source.

It also helps with rectification "artifacts", especially when you have Wide FOV lenses and you apply alpha param.

#### Usage:

```python
stereo.initialConfig.postProcessing.brightnessFilter.enable = True
stereo.initialConfig.postProcessing.brightnessFilter.minBrightness = 0  # Minimum brightness threshold
stereo.initialConfig.postProcessing.brightnessFilter.maxBrightness = 255  # Maximum brightness threshold
```

### Threshold Filter

Threshold filter will filter out all depth pixels outside the configured min/max threshold values. In a controlled environment,
where you know exactly how far the scene can be (eg. 30cm - 2m) it's advised to use this filter.

#### Usage:

```python
stereo.initialConfig.postProcessing.thresholdFilter.minRange = 0  # Minimum depth in cm
stereo.initialConfig.postProcessing.thresholdFilter.maxRange = 200  # Maximum depth in cm
```

### Decimation Filter

Decimation Filter will sub-sample the depth map, which means it reduces the depth scene complexity and allows other filters to run
faster. Setting decimationFactor to 2 will downscale 1280x800 depth map to 640x400. We can either select pixel skipping, median,
or mean decimation mode, and the latter two modes help with filtering as well. decimationFactor 1 disables the filter.

#### Usage:

```python
stereo.initialConfig.postProcessing.decimationFilter.decimationFactor = 2  # 1 = disabled, 2 = 2x downscale, etc.
```

### Filtering Order

The order of the filters is important, as the output of one filter is the input of the next filter. The order of the filters is
customizable:

#### Usage:

```python
config.postProcessing.filteringOrder = [
    dai.RawStereoDepthConfig.PostProcessing.Filter.TEMPORAL,
    dai.RawStereoDepthConfig.PostProcessing.Filter.SPECKLE,
    dai.RawStereoDepthConfig.PostProcessing.Filter.SPATIAL,
    dai.RawStereoDepthConfig.PostProcessing.Filter.MEDIAN,
    dai.RawStereoDepthConfig.PostProcessing.Filter.DECIMATION
]
stereo.initialConfig.set(config)
```

## Limitations

 * Median filter: On RVC4, median filter is implemented in software (CPU) and only supports 3x3 or 5x5 kernel sizes. If 7x7 is
   requested, it is automatically downgraded to 5x5.
 * Subpixel: Fixed to 4 bits on RVC4 (cannot be changed to 3 or 5 bits).
 * LR Check: Runs purely in software on CPU (not hardware-accelerated like on RVC2).

## Reference

### dai::node::StereoDepth

Kind: class

StereoDepth node. Compute stereo disparity and depth from left-right image pair.

#### std::uint32_t PresetMode

Kind: enum

Preset modes for stereo depth.

##### FAST_ACCURACY

Kind: enum_value

##### FAST_DENSITY

Kind: enum_value

##### DEFAULT

Kind: enum_value

##### FACE

Kind: enum_value

##### HIGH_DETAIL

Kind: enum_value

##### ROBOTICS

Kind: enum_value

##### DENSITY

Kind: enum_value

##### ACCURACY

Kind: enum_value

#### dai::StereoDepthConfig::MedianFilter MedianFilter

Kind: enum

#### std::shared_ptr< StereoDepthConfig > initialConfig

Kind: variable

Initial config to use for StereoDepth .

#### Input inputConfig

Kind: variable

Input StereoDepthConfig message with ability to modify parameters in runtime.

#### Input inputAlignTo

Kind: variable

Input align to message. Default queue is non-blocking with size 1.

#### Input left

Kind: variable

Input for left ImgFrame of left-right pair

#### Input right

Kind: variable

Input for right ImgFrame of left-right pair

#### Output depth

Kind: variable

Outputs ImgFrame message that carries RAW16 encoded (0..65535) depth data in depth units (millimeter by default). Non-determined /
invalid depth values are set to 0

#### Output disparity

Kind: variable

Outputs ImgFrame message that carries RAW8 / RAW16 encoded disparity data: RAW8 encoded (0..95) for standard mode; RAW8 encoded
(0..190) for extended disparity mode; RAW16 encoded for subpixel disparity mode: 0..760 for 3 fractional bits (by default);
0..1520 for 4 fractional bits; 0..3040 for 5 fractional bits

#### Output syncedLeft

Kind: variable

Passthrough ImgFrame message from 'left' Input.

#### Output syncedRight

Kind: variable

Passthrough ImgFrame message from 'right' Input.

#### Output rectifiedLeft

Kind: variable

Outputs ImgFrame message that carries RAW8 encoded (grayscale) rectified frame data.

#### Output rectifiedRight

Kind: variable

Outputs ImgFrame message that carries RAW8 encoded (grayscale) rectified frame data.

#### Output outConfig

Kind: variable

Outputs StereoDepthConfig message that contains current stereo configuration.

#### Output debugDispLrCheckIt1

Kind: variable

Outputs ImgFrame message that carries left-right check first iteration (before combining with second iteration) disparity map.
Useful for debugging/fine tuning.

#### Output debugDispLrCheckIt2

Kind: variable

Outputs ImgFrame message that carries left-right check second iteration (before combining with first iteration) disparity map.
Useful for debugging/fine tuning.

#### Output debugExtDispLrCheckIt1

Kind: variable

Outputs ImgFrame message that carries extended left-right check first iteration (downscaled frame, before combining with second
iteration) disparity map. Useful for debugging/fine tuning.

#### Output debugExtDispLrCheckIt2

Kind: variable

Outputs ImgFrame message that carries extended left-right check second iteration (downscaled frame, before combining with first
iteration) disparity map. Useful for debugging/fine tuning.

#### Output debugDispCostDump

Kind: variable

Outputs ImgFrame message that carries cost dump of disparity map. Useful for debugging/fine tuning.

#### Output confidenceMap

Kind: variable

Outputs ImgFrame message that carries RAW8 confidence map. Lower values mean lower confidence of the calculated disparity value.
RGB alignment, left-right check or any postprocessing (e.g., median filter) is not performed on confidence map.

#### StereoDepth()

Kind: function

#### std::shared_ptr< StereoDepth > build(Node::Output & left, Node::Output & right, PresetMode presetMode)

Kind: function

#### std::shared_ptr< StereoDepth > build(bool autoCreateCameras, PresetMode presetMode, std::pair< int, int > size,
std::optional< float > fps)

Kind: function

Create StereoDepth node. Note that this API is global and if used autocreated cameras can't be reused. parameters:
autoCreateCameras: If true, will create left and right nodes if they don't exist; presetMode: Preset mode for stereo depth

#### void loadMeshFiles(const std::filesystem::path & pathLeft, const std::filesystem::path & pathRight)

Kind: function

Specify local filesystem paths to the mesh calibration files for 'left' and 'right' inputs. When a mesh calibration is set, it
overrides the camera intrinsics/extrinsics matrices. Overrides useHomographyRectification behavior. Mesh format: a sequence of
(y,x) points as 'float' with coordinates from the input image to be mapped in the output. The mesh can be subsampled, configured
by With a 1280x800 resolution and the default (16,16) step, the required mesh size is: width: 1280 / 16 + 1 = 81 height: 800 / 16
+ 1 = 51

#### void loadMeshData(const std::vector< std::uint8_t > & dataLeft, const std::vector< std::uint8_t > & dataRight)

Kind: function

Specify mesh calibration data for 'left' and 'right' inputs, as vectors of bytes. Overrides useHomographyRectification behavior.
See

#### void setMeshStep(int width, int height)

Kind: function

Set the distance between mesh points. Default: (16, 16)

#### void setInputResolution(int width, int height)

Kind: function

Specify input resolution size Optional if MonoCamera exists, otherwise necessary

#### void setInputResolution(std::tuple< int, int > resolution)

Kind: function

Specify input resolution size Optional if MonoCamera exists, otherwise necessary

#### void setOutputSize(int width, int height)

Kind: function

Specify disparity/depth output resolution size, implemented by scaling. Currently only applicable when aligning to RGB camera

#### void setOutputKeepAspectRatio(bool keep)

Kind: function

Specifies whether the frames resized by

#### void setDepthAlign(Properties::DepthAlign align)

Kind: function

parameters: align: Set the disparity/depth alignment: centered (between the 'left' and 'right' inputs), or from the perspective of
a rectified output stream

#### void setDepthAlign(CameraBoardSocket camera)

Kind: function

parameters: camera: Set the camera from whose perspective the disparity/depth will be aligned

#### void setRectification(bool enable)

Kind: function

Rectify input images or not.

#### void setLeftRightCheck(bool enable)

Kind: function

Computes and combines disparities in both L-R and R-L directions, and combine them. For better occlusion handling, discarding
invalid disparity values

#### void setSubpixel(bool enable)

Kind: function

Computes disparity with sub-pixel interpolation (3 fractional bits by default). Suitable for long range. Currently incompatible
with extended disparity

#### void setSubpixelFractionalBits(int subpixelFractionalBits)

Kind: function

Number of fractional bits for subpixel mode. Default value: 3. Valid values: 3,4,5. Defines the number of fractional disparities:
2^x. Median filter postprocessing is supported only for 3 fractional bits.

#### void setExtendedDisparity(bool enable)

Kind: function

Disparity range increased from 0-95 to 0-190, combined from full resolution and downscaled images. Suitable for short range
objects. Currently incompatible with sub-pixel disparity

#### void setRectifyEdgeFillColor(int color)

Kind: function

Fill color for missing data at frame edges parameters: color: Grayscale 0..255, or -1 to replicate pixels

#### void setRuntimeModeSwitch(bool enable)

Kind: function

Enable runtime stereo mode switch, e.g. from standard to LR-check. Note: when enabled resources allocated for worst case to enable
switching to any mode.

#### void setNumFramesPool(int numFramesPool)

Kind: function

Specify number of frames in pool. parameters: numFramesPool: How many frames should the pool have

#### void setPostProcessingHardwareResources(int numShaves, int numMemorySlices)

Kind: function

Specify allocated hardware resources for stereo depth. Suitable only to increase post processing runtime. parameters: numShaves:
Number of shaves.; numMemorySlices: Number of memory slices.

#### void setDefaultProfilePreset(PresetMode mode)

Kind: function

Sets a default preset based on specified option. parameters: mode: Stereo depth preset mode

#### void useHomographyRectification(bool useHomographyRectification)

Kind: function

Use 3x3 homography matrix for stereo rectification instead of sparse mesh generated on device. Default behaviour is AUTO, for
lenses with FOV over 85 degrees sparse mesh is used, otherwise 3x3 homography. If custom mesh data is provided through
loadMeshData or loadMeshFiles this option is ignored. parameters: useHomographyRectification: true: 3x3 homography matrix
generated from calibration data is used for stereo rectification, can't correct lens distortion. false: sparse mesh is generated
on-device from calibration data with mesh step specified with setMeshStep (Default: (16, 16)), can correct lens distortion.
Implementation for generating the mesh is same as opencv's initUndistortRectifyMap function. Only the first 8 distortion
coefficients are used from calibration data.

#### void enableDistortionCorrection(bool enableDistortionCorrection)

Kind: function

Equivalent to useHomographyRectification(!enableDistortionCorrection)

#### void setFrameSync(bool enableFrameSync)

Kind: function

Whether to enable frame syncing inside stereo node or not. Suitable if inputs are known to be synced.

#### void setBaseline(float baseline)

Kind: function

Override baseline from calibration. Used only in disparity to depth conversion. Units are centimeters.

#### void setFocalLength(float focalLength)

Kind: function

Override focal length from calibration. Used only in disparity to depth conversion. Units are pixels.

#### void setDisparityToDepthUseSpecTranslation(bool specTranslation)

Kind: function

Use baseline information for disparity to depth conversion from specs (design data) or from calibration. Default: true

#### void setRectificationUseSpecTranslation(bool specTranslation)

Kind: function

Obtain rectification matrices using spec translation (design data) or from calibration in calculations. Should be used only for
debugging. Default: false

#### void setDepthAlignmentUseSpecTranslation(bool specTranslation)

Kind: function

Use baseline information for depth alignment from specs (design data) or from calibration. Default: true

#### void setAlphaScaling(float alpha)

Kind: function

Free scaling parameter between 0 (when all the pixels in the undistorted image are valid) and 1 (when all the source image pixels
are retained in the undistorted image). On some high distortion lenses, and/or due to rectification (image rotated) invalid areas
may appear even with alpha=0, in these cases alpha < 0.0 helps removing invalid areas. See getOptimalNewCameraMatrix from opencv
for more details.

### dai::StereoDepthConfig

Kind: class

StereoDepthConfig message.

#### dai::StereoDepthConfig::AlgorithmControl

Kind: struct

##### int32_t DepthAlign

Kind: enum

Align the disparity/depth to the perspective of a rectified output, or center it

###### AUTO

Kind: enum_value

###### RECTIFIED_RIGHT

Kind: enum_value

###### RECTIFIED_LEFT

Kind: enum_value

###### CENTER

Kind: enum_value

###### RIGHT

Kind: enum_value

###### LEFT

Kind: enum_value

##### dai::DepthUnit DepthUnit

Kind: enum

##### DepthAlign depthAlign

Kind: variable

Set the disparity/depth alignment to the perspective of a rectified output, or center it

##### DepthUnit depthUnit

Kind: variable

Measurement unit for depth data. Depth data is integer value, multiple of depth unit.

##### float customDepthUnitMultiplier

Kind: variable

Custom depth unit multiplier, if custom depth unit is enabled, relative to 1 meter. A multiplier of 1000 effectively means depth
unit in millimeter.

##### bool enableLeftRightCheck

Kind: variable

Computes and combines disparities in both L-R and R-L directions, and combine them. For better occlusion handling

##### bool enableSwLeftRightCheck

Kind: variable

Enables software left right check. Applicable to RVC4 only.

##### bool enableExtended

Kind: variable

Disparity range increased from 95 to 190, combined from full resolution and downscaled images. Suitable for short range objects

##### bool enableSubpixel

Kind: variable

Computes disparity with sub-pixel interpolation (5 fractional bits), suitable for long range

##### std::int32_t leftRightCheckThreshold

Kind: variable

Left-right check threshold for left-right, right-left disparity map combine, 0..128 Used only when left-right check mode is
enabled. Defines the maximum difference between the confidence of pixels from left-right and right-left confidence maps

##### std::int32_t subpixelFractionalBits

Kind: variable

Number of fractional bits for subpixel mode Valid values: 3,4,5 Defines the number of fractional disparities: 2^x Median filter
postprocessing is supported only for 3 fractional bits

##### std::int32_t disparityShift

Kind: variable

Shift input frame by a number of pixels to increase minimum depth. For example shifting by 48 will change effective disparity
search range from (0,95] to [48,143]. An alternative approach to reducing the minZ. We normally only recommend doing this when it
is known that there will be no objects farther away than MaxZ, such as having a depth camera mounted above a table pointing down
at the table surface.

##### std::optional< float > centerAlignmentShiftFactor

Kind: variable

##### std::int32_t numInvalidateEdgePixels

Kind: variable

Invalidate X amount of pixels at the edge of disparity frame. For right and center alignment X pixels will be invalidated from the
right edge, for left alignment from the left edge.

##### DEPTHAI_SERIALIZE(AlgorithmControl, depthAlign, depthUnit, customDepthUnitMultiplier, enableLeftRightCheck,
enableSwLeftRightCheck, enableExtended, enableSubpixel, leftRightCheckThreshold, subpixelFractionalBits, disparityShift,
centerAlignmentShiftFactor, numInvalidateEdgePixels)

Kind: function

#### dai::StereoDepthConfig::CensusTransform

Kind: struct

The basic cost function used by the Stereo Accelerator for matching the left and right images is the Census Transform . It works
on a block of pixels and computes a bit vector which represents the structure of the image in that block. There are two types of
Census Transform based on how the middle pixel is used: Classic Approach and Modified Census. The comparisons that are made
between pixels can be or not thresholded. In some cases a mask can be applied to filter out only specific bits from the entire bit
stream. All these approaches are: Classic Approach: Uses middle pixel to compare against all its neighbors over a defined window.
Each comparison results in a new bit, that is 0 if central pixel is smaller, or 1 if is it bigger than its neighbor. Modified
Census Transform : same as classic Census Transform , but instead of comparing central pixel with its neighbors, the window mean
will be compared with each pixel over the window. Thresholding Census Transform : same as classic Census Transform , but it is not
enough that a neighbor pixel to be bigger than the central pixel, it must be significant bigger (based on a threshold). Census
Transform with Mask: same as classic Census Transform , but in this case not all of the pixel from the support window are part of
the binary descriptor. We use a ma sk “M” to define which pixels are part of the binary descriptor (1), and which pixels should be
skipped (0).

##### std::int32_t KernelSize

Kind: enum

Census transform kernel size possible values.

###### AUTO

Kind: enum_value

###### KERNEL_5x5

Kind: enum_value

###### KERNEL_7x7

Kind: enum_value

###### KERNEL_7x9

Kind: enum_value

##### KernelSize kernelSize

Kind: variable

Census transform kernel size.

##### uint64_t kernelMask

Kind: variable

Census transform mask, default - auto, mask is set based on resolution and kernel size. Disabled for 400p input resolution.
Enabled for 720p. 0XA82415 for 5x5 census transform kernel. 0XAA02A8154055 for 7x7 census transform kernel. 0X2AA00AA805540155 for
7x9 census transform kernel. Empirical values.

##### bool enableMeanMode

Kind: variable

If enabled, each pixel in the window is compared with the mean window value instead of the central pixel.

##### uint32_t threshold

Kind: variable

Census transform comparison threshold value.

##### int8_t noiseThresholdOffset

Kind: variable

Used to reduce small fixed levels of noise across all luminance values in the current image. Valid range is [0,127]. Default value
is 0.

##### int8_t noiseThresholdScale

Kind: variable

Used to reduce noise values that increase with luminance in the current image. Valid range is [-128,127]. Default value is 0.

##### DEPTHAI_SERIALIZE(CensusTransform, kernelSize, kernelMask, enableMeanMode, threshold, noiseThresholdOffset,
noiseThresholdScale)

Kind: function

#### dai::StereoDepthConfig::ConfidenceMetrics

Kind: struct

##### uint8_t occlusionConfidenceWeight

Kind: variable

Weight used with occlusion estimation to generate final confidence map. Valid range is [0,32]

##### uint8_t motionVectorConfidenceWeight

Kind: variable

Weight used with local neighborhood motion vector variance estimation to generate final confidence map. Valid range is [0,32].

##### uint8_t motionVectorConfidenceThreshold

Kind: variable

Threshold offset for MV variance in confidence generation. A value of 0 allows most variance. Valid range is [0,3].

##### uint8_t flatnessConfidenceWeight

Kind: variable

Weight used with flatness estimation to generate final confidence map. Valid range is [0,32].

##### uint8_t flatnessConfidenceThreshold

Kind: variable

Threshold for flatness check in SGM block. Valid range is [1,7].

##### bool flatnessOverride

Kind: variable

Flag to indicate whether final confidence value will be overidden by flatness value. Valid range is {true,false}.

##### DEPTHAI_SERIALIZE(ConfidenceMetrics, occlusionConfidenceWeight, motionVectorConfidenceWeight,
motionVectorConfidenceThreshold, flatnessConfidenceWeight, flatnessConfidenceThreshold, flatnessOverride)

Kind: function

#### dai::StereoDepthConfig::CostAggregation

Kind: struct

Cost Aggregation is based on Semi Global Block Matching (SGBM). This algorithm uses a semi global technique to aggregate the cost
map. Ultimately the idea is to build inertia into the stereo algorithm. If a pixel has very little texture information, then odds
are the correct disparity for this pixel is close to that of the previous pixel considered. This means that we get improved
results in areas with low texture.

##### dai::StereoDepthConfig::CostAggregation::P1Config

Kind: struct

Structure for adaptive P1 penalty configuration.

###### bool enableAdaptive

Kind: variable

Used to disable/enable adaptive penalty.

###### uint8_t defaultValue

Kind: variable

Used as the default penalty value when nAdapEnable is disabled. A bigger value enforces higher smoothness and reduced noise at the
cost of lower edge accuracy. This value must be smaller than P2 default penalty. Valid range is [10,50].

###### uint8_t edgeValue

Kind: variable

Penalty value on edges when nAdapEnable is enabled. A smaller penalty value permits higher change in disparity. This value must be
smaller than or equal to P2 edge penalty. Valid range is [10,50].

###### uint8_t smoothValue

Kind: variable

Penalty value on low texture regions when nAdapEnable is enabled. A smaller penalty value permits higher change in disparity. This
value must be smaller than or equal to P2 smoothness penalty. Valid range is [10,50].

###### uint8_t edgeThreshold

Kind: variable

Threshold value on edges when nAdapEnable is enabled. A bigger value permits higher neighboring feature dissimilarity tolerance.
This value is shared with P2 penalty configuration. Valid range is [8,16].

###### uint8_t smoothThreshold

Kind: variable

Threshold value on low texture regions when nAdapEnable is enabled. A bigger value permits higher neighboring feature
dissimilarity tolerance. This value is shared with P2 penalty configuration. Valid range is [2,12].

###### DEPTHAI_SERIALIZE(P1Config, enableAdaptive, defaultValue, edgeValue, smoothValue, edgeThreshold, smoothThreshold)

Kind: function

##### dai::StereoDepthConfig::CostAggregation::P2Config

Kind: struct

Structure for adaptive P2 penalty configuration.

###### bool enableAdaptive

Kind: variable

Used to disable/enable adaptive penalty.

###### uint8_t defaultValue

Kind: variable

Used as the default penalty value when nAdapEnable is disabled. A bigger value enforces higher smoothness and reduced noise at the
cost of lower edge accuracy. This value must be larger than P1 default penalty. Valid range is [20,100].

###### uint8_t edgeValue

Kind: variable

Penalty value on edges when nAdapEnable is enabled. A smaller penalty value permits higher change in disparity. This value must be
larger than or equal to P1 edge penalty. Valid range is [20,100].

###### uint8_t smoothValue

Kind: variable

Penalty value on low texture regions when nAdapEnable is enabled. A smaller penalty value permits higher change in disparity. This
value must be larger than or equal to P1 smoothness penalty. Valid range is [20,100].

###### DEPTHAI_SERIALIZE(P2Config, enableAdaptive, defaultValue, edgeValue, smoothValue)

Kind: function

##### uint8_t divisionFactor

Kind: variable

Cost calculation linear equation parameters.

##### uint16_t horizontalPenaltyCostP1

Kind: variable

Horizontal P1 penalty cost parameter.

##### uint16_t horizontalPenaltyCostP2

Kind: variable

Horizontal P2 penalty cost parameter.

##### uint16_t verticalPenaltyCostP1

Kind: variable

Vertical P1 penalty cost parameter.

##### uint16_t verticalPenaltyCostP2

Kind: variable

Vertical P2 penalty cost parameter.

##### P1Config p1Config

Kind: variable

##### P2Config p2Config

Kind: variable

##### DEPTHAI_SERIALIZE(CostAggregation, divisionFactor, horizontalPenaltyCostP1, horizontalPenaltyCostP2, verticalPenaltyCostP1,
verticalPenaltyCostP2, p1Config, p2Config)

Kind: function

#### dai::StereoDepthConfig::CostMatching

Kind: struct

The matching cost is way of measuring the similarity of image locations in stereo correspondence algorithm. Based on the
configuration parameters and based on the descriptor type, a linear equation is applied to computing the cost for each candidate
disparity at each pixel.

##### dai::StereoDepthConfig::CostMatching::LinearEquationParameters

Kind: struct

The linear equation applied for computing the cost is: COMB_COST = α*AD + β*(CTC<<3). CLAMP(COMB_COST >> 5, threshold). Where AD
is the Absolute Difference between 2 pixels values. CTC is the Census Transform Cost between 2 pixels, based on Hamming distance
(xor). The α and β parameters are subject to fine tuning by the user.

###### uint8_t alpha

Kind: variable

###### uint8_t beta

Kind: variable

###### uint8_t threshold

Kind: variable

###### DEPTHAI_SERIALIZE(LinearEquationParameters, alpha, beta, threshold)

Kind: function

##### std::uint32_t DisparityWidth

Kind: enum

Disparity search range: 64 or 96 pixels are supported by the HW.

###### DISPARITY_64

Kind: enum_value

###### DISPARITY_96

Kind: enum_value

##### DisparityWidth disparityWidth

Kind: variable

Disparity search range, default 96 pixels.

##### bool enableCompanding

Kind: variable

Disparity companding using sparse matching. Matching pixel by pixel for N disparities. Matching every 2nd pixel for M
disparitites. Matching every 4th pixel for T disparities. In case of 96 disparities: N=48, M=32, T=16. This way the search range
is extended to 176 disparities, by sparse matching. Note: when enabling this flag only depth map will be affected, disparity map
is not.

##### uint8_t invalidDisparityValue

Kind: variable

Used only for debug purposes, SW postprocessing handled only invalid value of 0 properly.

##### uint8_t confidenceThreshold

Kind: variable

Disparities with confidence value over this threshold are accepted.

##### bool enableSwConfidenceThresholding

Kind: variable

Enable software confidence thresholding. Applicable to RVC4 only.

##### LinearEquationParameters linearEquationParameters

Kind: variable

Cost calculation linear equation parameters.

##### DEPTHAI_SERIALIZE(CostMatching, disparityWidth, enableCompanding, invalidDisparityValue, confidenceThreshold,
enableSwConfidenceThresholding, linearEquationParameters)

Kind: function

#### dai::StereoDepthConfig::PostProcessing

Kind: struct

Post-processing filters, all the filters are applied in disparity domain.

##### dai::StereoDepthConfig::PostProcessing::AdaptiveMedianFilter

Kind: struct

###### bool enable

Kind: variable

Flag to enable adaptive median filtering for a final pass of filtering on low confidence pixels.

###### uint8_t confidenceThreshold

Kind: variable

Confidence threshold for adaptive median filtering. Should be less than nFillConfThresh value used in evaDfsHoleFillConfig. Valid
range is [0,255].

###### DEPTHAI_SERIALIZE(AdaptiveMedianFilter, enable, confidenceThreshold)

Kind: function

##### dai::StereoDepthConfig::PostProcessing::BrightnessFilter

Kind: struct

Brightness filtering. If input frame pixel is too dark or too bright, disparity will be invalidated. The idea is that for too
dark/too bright pixels we have low confidence, since that area was under/over exposed and details were lost.

###### std::int32_t minBrightness

Kind: variable

Minimum pixel brightness. If input pixel is less or equal than this value the depth value is invalidated.

###### std::int32_t maxBrightness

Kind: variable

Maximum range in depth units. If input pixel is less or equal than this value the depth value is invalidated.

###### DEPTHAI_SERIALIZE(BrightnessFilter, minBrightness, maxBrightness)

Kind: function

##### dai::StereoDepthConfig::PostProcessing::DecimationFilter

Kind: struct

Decimation filter. Reduces the depth scene complexity. The filter runs on kernel sizes [2x2] to [8x8] pixels.

###### int32_t DecimationMode

Kind: enum

Decimation algorithm type.

###### PIXEL_SKIPPING

Kind: enum_value

###### NON_ZERO_MEDIAN

Kind: enum_value

###### NON_ZERO_MEAN

Kind: enum_value

###### std::uint32_t decimationFactor

Kind: variable

Decimation factor. Valid values are 1,2,3,4. Disparity/depth map x/y resolution will be decimated with this value.

###### DecimationMode decimationMode

Kind: variable

Decimation algorithm type.

###### DEPTHAI_SERIALIZE(DecimationFilter, decimationFactor, decimationMode)

Kind: function

##### dai::StereoDepthConfig::PostProcessing::HoleFilling

Kind: struct

###### bool enable

Kind: variable

Flag to enable post-processing hole-filling.

###### uint8_t highConfidenceThreshold

Kind: variable

Pixels with confidence higher than this value are used to calculate an average disparity per superpixel. Valid range is [1,255]

###### uint8_t fillConfidenceThreshold

Kind: variable

Pixels with confidence below this value will be filled with the average disparity of their corresponding superpixel. Valid range
is [1,255].

###### uint8_t minValidDisparity

Kind: variable

Represents the required percentange of pixels with confidence value above nHighConfThresh that are used to calculate average
disparity per superpixel, where 1 means 50% or half, 2 means 25% or a quarter and 3 means 12.5% or an eighth. If the required
number of pixels are not found, the holes will not be filled.

###### bool invalidateDisparities

Kind: variable

If enabled, sets to 0 the disparity of pixels with confidence below nFillConfThresh, which did not pass nMinValidPixels criteria.
Valid range is {true, false}.

###### DEPTHAI_SERIALIZE(HoleFilling, enable, highConfidenceThreshold, fillConfidenceThreshold, minValidDisparity,
invalidateDisparities)

Kind: function

##### dai::StereoDepthConfig::PostProcessing::ThresholdFilter

Kind: struct

Threshold filtering. Filters out distances outside of a given interval.

###### std::int32_t minRange

Kind: variable

Minimum range in depth units. Depth values under this value are invalidated.

###### std::int32_t maxRange

Kind: variable

Maximum range in depth units. Depth values over this value are invalidated.

###### DEPTHAI_SERIALIZE(ThresholdFilter, minRange, maxRange)

Kind: function

##### int32_t Filter

Kind: enum

###### NONE

Kind: enum_value

###### DECIMATION

Kind: enum_value

###### SPECKLE

Kind: enum_value

###### MEDIAN

Kind: enum_value

###### SPATIAL

Kind: enum_value

###### TEMPORAL

Kind: enum_value

###### FILTER_COUNT

Kind: enum_value

##### filters::params::SpatialFilter SpatialFilter

Kind: enum

##### filters::params::TemporalFilter TemporalFilter

Kind: enum

##### filters::params::SpeckleFilter SpeckleFilter

Kind: enum

##### std::array< Filter, 5 > filteringOrder

Kind: variable

Order of filters to be applied if filtering is enabled.

##### MedianFilter median

Kind: variable

Set kernel size for disparity/depth median filtering, or disable

##### std::int16_t bilateralSigmaValue

Kind: variable

Sigma value for bilateral filter. 0 means disabled. A larger value of the parameter means that farther colors within the pixel
neighborhood will be mixed together.

##### SpatialFilter spatialFilter

Kind: variable

Edge-preserving filtering: This type of filter will smooth the depth noise while attempting to preserve edges.

##### TemporalFilter temporalFilter

Kind: variable

Temporal filtering with optional persistence.

##### ThresholdFilter thresholdFilter

Kind: variable

Threshold filtering. Filters out distances outside of a given interval.

##### BrightnessFilter brightnessFilter

Kind: variable

Brightness filtering. If input frame pixel is too dark or too bright, disparity will be invalidated. The idea is that for too
dark/too bright pixels we have low confidence, since that area was under/over exposed and details were lost.

##### SpeckleFilter speckleFilter

Kind: variable

Speckle filtering. Removes speckle noise.

##### DecimationFilter decimationFilter

Kind: variable

Decimation filter. Reduces disparity/depth map x/y complexity, reducing runtime complexity for other filters.

##### HoleFilling holeFilling

Kind: variable

##### AdaptiveMedianFilter adaptiveMedianFilter

Kind: variable

##### DEPTHAI_SERIALIZE(PostProcessing, filteringOrder, median, bilateralSigmaValue, spatialFilter, temporalFilter,
thresholdFilter, brightnessFilter, speckleFilter, decimationFilter, holeFilling, adaptiveMedianFilter)

Kind: function

#### filters::params::MedianFilter MedianFilter

Kind: enum

#### AlgorithmControl algorithmControl

Kind: variable

Controls the flow of stereo algorithm - left-right check, subpixel etc.

#### PostProcessing postProcessing

Kind: variable

Controls the postprocessing of disparity and/or depth map.

#### CensusTransform censusTransform

Kind: variable

Census transform settings.

#### CostMatching costMatching

Kind: variable

Cost matching settings.

#### CostAggregation costAggregation

Kind: variable

Cost aggregation settings.

#### ConfidenceMetrics confidenceMetrics

Kind: variable

Confidence metrics settings.

#### dai::ProcessorType filtersBackend

Kind: variable

#### StereoDepthConfig()

Kind: function

Construct StereoDepthConfig message.

#### ~StereoDepthConfig()

Kind: function

#### StereoDepthConfig & setDepthAlign(AlgorithmControl::DepthAlign align)

Kind: function

parameters: align: Set the disparity/depth alignment: centered (between the 'left' and 'right' inputs), or from the perspective of
a rectified output stream

#### StereoDepthConfig & setConfidenceThreshold(int confThr)

Kind: function

Confidence threshold for disparity calculation parameters: confThr: Confidence threshold value 0..255

#### int getConfidenceThreshold()

Kind: function

Get confidence threshold for disparity calculation

#### StereoDepthConfig & setMedianFilter(MedianFilter median)

Kind: function

parameters: median: Set kernel size for disparity/depth median filtering, or disable

#### MedianFilter getMedianFilter()

Kind: function

Get median filter setting

#### StereoDepthConfig & setBilateralFilterSigma(uint16_t sigma)

Kind: function

A larger value of the parameter means that farther colors within the pixel neighborhood will be mixed together, resulting in
larger areas of semi-equal color. parameters: sigma: Set sigma value for 5x5 bilateral filter. 0..65535

#### uint16_t getBilateralFilterSigma()

Kind: function

Get sigma value for 5x5 bilateral filter

#### StereoDepthConfig & setLeftRightCheckThreshold(int threshold)

Kind: function

parameters: threshold: Set threshold for left-right, right-left disparity map combine, 0..255

#### int getLeftRightCheckThreshold()

Kind: function

Get threshold for left-right check combine

#### StereoDepthConfig & setLeftRightCheck(bool enable)

Kind: function

Computes and combines disparities in both L-R and R-L directions, and combine them. For better occlusion handling, discarding
invalid disparity values

#### bool getLeftRightCheck()

Kind: function

Get left-right check setting

#### StereoDepthConfig & setExtendedDisparity(bool enable)

Kind: function

Disparity range increased from 95 to 190, combined from full resolution and downscaled images. Suitable for short range objects

#### bool getExtendedDisparity()

Kind: function

Get extended disparity setting

#### StereoDepthConfig & setSubpixel(bool enable)

Kind: function

Computes disparity with sub-pixel interpolation (3 fractional bits by default). Suitable for long range. Currently incompatible
with extended disparity

#### bool getSubpixel()

Kind: function

Get subpixel setting

#### StereoDepthConfig & setSubpixelFractionalBits(int subpixelFractionalBits)

Kind: function

Number of fractional bits for subpixel mode. Default value: 3. Valid values: 3,4,5. Defines the number of fractional disparities:
2^x. Median filter postprocessing is supported only for 3 fractional bits.

#### int getSubpixelFractionalBits()

Kind: function

Get number of fractional bits for subpixel mode

#### StereoDepthConfig & setDepthUnit(AlgorithmControl::DepthUnit depthUnit)

Kind: function

Set depth unit of depth map. Meter, centimeter, millimeter, inch, foot or custom unit is available.

#### AlgorithmControl::DepthUnit getDepthUnit()

Kind: function

Get depth unit of depth map.

#### StereoDepthConfig & setCustomDepthUnitMultiplier(float multiplier)

Kind: function

Set custom depth unit multiplier relative to 1 meter.

#### float getCustomDepthUnitMultiplier()

Kind: function

Get custom depth unit multiplier relative to 1 meter.

#### StereoDepthConfig & setDisparityShift(int disparityShift)

Kind: function

Shift input frame by a number of pixels to increase minimum depth. For example shifting by 48 will change effective disparity
search range from (0,95] to [48,143]. An alternative approach to reducing the minZ. We normally only recommend doing this when it
is known that there will be no objects farther away than MaxZ, such as having a depth camera mounted above a table pointing down
at the table surface.

#### StereoDepthConfig & setNumInvalidateEdgePixels(int32_t numInvalidateEdgePixels)

Kind: function

Invalidate X amount of pixels at the edge of disparity frame. For right and center alignment X pixels will be invalidated from the
right edge, for left alignment from the left edge.

#### StereoDepthConfig & setFiltersComputeBackend(dai::ProcessorType filtersBackend)

Kind: function

Set filters compute backend

#### dai::ProcessorType getFiltersComputeBackend()

Kind: function

Get filters compute backend

#### float getMaxDisparity()

Kind: function

Useful for normalization of the disparity map. return: Maximum disparity value that the node can return

#### void serialize(std::vector< std::uint8_t > & metadata, DatatypeEnum & datatype)

Kind: function

#### DatatypeEnum getDatatype()

Kind: function

Get the datatype of this specific message.

return: DatatypeEnum

#### DEPTHAI_SERIALIZE(StereoDepthConfig, algorithmControl, postProcessing, censusTransform, costMatching, costAggregation,
confidenceMetrics, filtersBackend)

Kind: function

### Need assistance?

Head over to [Discussion Forum](https://discuss.luxonis.com/) for technical support or any other questions you might have.
