# Configuring Stereo Depth

Our [StereoDepth node](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/stereo_depth.md) is very configurable
and with this tutorial we will go over some configurations and troubleshooting you can do to get the best results.

This documentation is divided into 7 chapters:

 1. [Stereo Depth Basics](#Stereo%20Depth%20Basics)
 2. [Stereo Depth Preset specifications](#Stereo%20Depth%20Preset%20specifications)
 3. [Fixing noisy depth](#Fixing%20noisy%20depth)
 4. [Improving depth accuracy](#Improving%20depth%20accuracy)
 5. [Short range stereo depth](#Short%20range%20stereo%20depth)
 6. [Long range stereo depth](#Long%20range%20stereo%20depth)
 7. [Fixing noisy pointcloud](#Fixing%20noisy%20pointcloud)

### Stereo Depth Basics

[Stereo depth vision](https://en.wikipedia.org/wiki/Computer_stereo_vision) works by calculating the disparity between two images
taken from slightly different points.

Stereo vision works a lot like our eyes. Our brains (subconsciously) estimate the depth of objects and scenes based on the
difference between what our left eye sees versus what our right eye sees. On OAK-D cameras, it's exactly the same; we have left
and right cameras (of the stereo camera pair) and the OAK does on-device disparity matching to estimate the depth of objects and
scenes.

Disparity refers to the distance between two corresponding points in the left and right image of a stereo pair.

### Depth from disparity

Let's first look at how the depth is calculated:

 * depth_cm - depth in centimeters
 * fx_px - [focal length](#Configuring%2520Stereo%2520Depth-Focal%2520Length) in pixels
 * baseline_cm - distance between two cameras of the stereo camera pair
 * disparity_px - disparity in pixels

Examples for calculating the depth value, using the OAK-D (7.5cm baseline OV9282), for 400P resolution and disparity of 50 pixels:

#### Focal Length

Focal length is the distance between the camera lens and the image sensor. The larger the focal length, the narrower the FOV.

You can read the camera's focal length (in pixels) from calibration, see the [calibration dump
here](https://docs.luxonis.com/software-v3/depthai/examples/calibration/calibration_dump.md). The value itself varies depending on
the camera model and resolution.

Recommended approach: Use [ImgTransformations](https://docs.luxonis.com/software-v3/depthai/api/cpp.md) to get the intrinsics
matrix, as it is the main source of truth for the actual transformations applied to the image frames:

```python
import depthai as dai

# Get intrinsics from ImgTransformations (recommended)
disparity = disparityQueue.get()  # or depthQueue.get()
intrinsics = disparity.getTransformation().getSourceIntrinsicMatrix()
print('Focal length in pixels:', intrinsics[0][0])
```

Alternative approach: You can also read the camera's focal length from calibration:

```python
import depthai as dai

with dai.Device() as device:
  calibData = device.readCalibration()
  intrinsics = calibData.getCameraIntrinsics(dai.CameraBoardSocket.CAM_C)
  print('Right mono camera focal length in pixels:', intrinsics[0][0])
```

The focal length in pixels is written in camera intrinsics (intrinsics[0][0]):

#### Disparity

Disparity and depth are inversely related. As disparity decreases, the depth increases exponentially depending on the 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 some change in disparity doesn't lead to a large change in depth (better
accuracy).

Here's a graph showing disparity vs depth for OAK-D (7.5cm baseline distance) at 800P:

[Full chart here](https://docs.google.com/spreadsheets/d/1ymn-0D4HcCbzYP-iPycj_PIdSwmrLenlGryuZDyA4rQ/edit#gid=0)

Note the value of depth data is stored in uint16, where 0 means that the distance is invalid/unknown.

### How baseline distance and focal length affect depth

Looking at the depth formula above, we can see that either a larger baseline distance or a larger focal length will result in
further depth at the same disparity, which means that the depth accuracy will be better.

So to get long-range depth perception, you can increase the baseline distance and/or decrease the FOV.

> Wider FOV will result in worse depth accuracy, even at shorter ranges (where accuracy drop isn't as noticeable).

### Min stereo depth distance

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.

You can calculate the minimum stereo depth distance, 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 the maximum value for disparity_in_pixels parameter (keep in
mind it is inveresly related, so maximum value will yield the smallest result). We have:

or roughly 70cm.

However this distance can be cut in 1/2 (to around 35cm for the OAK-D) with the following options:

 1. Changing the resolution to 640x400, instead of the standard 1280x800.

 2. Enabling Extended Disparity.

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 [Currently configurable
blocks](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/stereo_depth.md).

Using the previous OAK-D example, disparity_in_pixels now becomes 190 and the minimum distance is:

```python
min_distance = focal_length_in_pixels * baseline / disparity_in_pixels = 882.5 * 7.5cm / 190 = 34.84cm
```

or roughly 35cm.

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

See [these
examples](https://github.com/luxonis/oak-examples/tree/master/gen2-camera-demo#real-time-depth-from-depthai-stereo-pair) for how
to enable Extended Disparity.

#### Move the camera closer to the object

Looking at the [Depth from disparity](#Configuring%2520Stereo%2520Depth-Depth%2520from%2520disparity) section, from the graph it's
clear that at the 95 disparity pixels (close distance), depth change between disparity pixels (eg. 95->94) is the lowest, so the
depth accuracy is the best.

Depth accuracy decreases exponentially with the distance from the camera. Note that with [Stereo Subpixel
mode](#Configuring%2520Stereo%2520Depth-Stereo%2520Subpixel%2520mode) enabled you can have better depth accuracy (even at a longer
distance) but it only works to some extent.

So to conclude, object/scene you are measuring should be as close as possible to MinZ (minimal depth perception) of the camera for
best depth accuracy. You can find MinZ specification for each device in the [Hardware
documentation](https://docs.luxonis.com/hardware.md).

### Max stereo depth distance

The maximum depth perception distance depends on [how baseline distance and focal length affect
depth](#Configuring%2520Stereo%2520Depth-How%2520baseline%2520distance%2520and%2520focal%2520length%2520affect%2520depth). The
formula used to calculate this distance is an approximation, but is as follows:

```python
Dm = (baseline/2) * tan((90 - HFOV / HPixels)*pi/180)
```

So using this formula for existing models the theoretical max distance is:

```python
# For OAK-D (7.5cm baseline)
Dm = (7.5/2) * tan((90 - 71.9/1280)*pi/180) = 3825.03cm = 38.25 meters

# For OAK-D-CM4 (9cm baseline)
Dm = (9/2) * tan((90 - 71.9/1280)*pi/180) = 4590.04cm = 45.9 meters
```

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/hardware/products/OAK-FFC%25204P.md) device or design your own baseboard PCB with required
baseline. For more information see Subpixel Disparity under the Stereo Mode tab in [Currently configurable
blocks](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/stereo_depth.md).

### Stereo Depth Preset specifications

The StereoDepth node provides several profile presets that can be used to quickly configure the node for different scenarios. Each
preset applies a specific combination of filters and parameters optimized for particular use cases.

For information about FPS performance for each preset, see the [Platform-Specific
Configuration](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/stereo_depth.md).

#### RVC2

### Available Presets

RVC2 supports the following presets:

 * DEFAULT: General purpose configuration with balanced settings
 * ROBOTICS: Optimized for navigation and obstacle detection, without motion blur
 * FACE: Optimized for face tracking (short range)
 * HIGH_DETAIL: Designed to capture fine details and small objects in the scene, prioritizing maximum detail while accepting
   increased noise for enhanced feature visibility
 * FAST_DENSITY: Prioritizes high fill-rate and with faster processing
 * FAST_ACCURACY: Prioritizes high accuracy with faster processing but lower fill-rate

### Preset-Specific Differences

For details on the filters, see [Platform-Specific
Configuration](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/stereo_depth.md).

DEFAULT Preset:

 * Extended Disparity: False
 * Subpixel: True (3 bits)
 * Left-Right Check: True
 * Median Filter: KERNEL_7x7
 * Spatial Filter: enable=True, delta=3, holeFillingRadius=1
 * Speckle Filter: enable=True, speckleRange=200
 * Temporal Filter: enable=True, alpha=0.5
 * Decimation Filter: decimationFactor=2
 * Threshold Filter: 0 to 15 meters (minRange=0, maxRange=15000)
 * Confidence Threshold: 15

ROBOTICS Preset:

 * Extended Disparity: False
 * Subpixel: True (3 bits)
 * Left-Right Check: True
 * Median Filter: KERNEL_7x7
 * Spatial Filter: enable=True, delta=20, holeFillingRadius=2
 * Speckle Filter: enable=True, speckleRange=200
 * Temporal Filter: enable=False
 * Decimation Filter: decimationFactor=2
 * Threshold Filter: 0 to 10 meters (minRange=0, maxRange=10000)
 * Confidence Threshold: 15

FACE Preset:

 * Extended Disparity: True
 * Subpixel: True (5 bits)
 * Left-Right Check: True
 * Median Filter: MEDIAN_OFF
 * Spatial Filter: enable=True, delta=3, holeFillingRadius=1
 * Speckle Filter: enable=True, speckleRange=200
 * Temporal Filter: enable=True, alpha=0.5
 * Decimation Filter: decimationFactor=2
 * Threshold Filter: 0.03 to 3 meters (minRange=30, maxRange=3000)
 * Confidence Threshold: 15

HIGH_DETAIL Preset:

 * Extended Disparity: True
 * Subpixel: True (5 bits)
 * Left-Right Check: True (threshold: 5)
 * Median Filter: MEDIAN_OFF
 * Spatial Filter: enable=True, delta=3, holeFillingRadius=1
 * Speckle Filter: enable=True, speckleRange=200
 * Temporal Filter: enable=True, alpha=0.5
 * Decimation Filter: decimationFactor=2
 * Threshold Filter: 0 to 15 meters (minRange=0, maxRange=15000)
 * Confidence Threshold: 55

FAST_DENSITY Preset:

 * Extended Disparity: False
 * Subpixel: True (5 bits)
 * Left-Right Check: True
 * Median Filter: MEDIAN_OFF
 * Spatial Filter: enable=False
 * Speckle Filter: enable=False
 * Temporal Filter: enable=False
 * Decimation Filter: decimationFactor=1 (disabled)
 * Max Disparity: 3040.0 (reduced for speed)
 * Confidence Threshold: 15

FAST_ACCURACY Preset:

 * Extended Disparity: False
 * Subpixel: True (5 bits)
 * Left-Right Check: True (threshold: 5)
 * Median Filter: MEDIAN_OFF
 * Spatial Filter: enable=False
 * Speckle Filter: enable=False
 * Temporal Filter: enable=False
 * Decimation Filter: decimationFactor=1 (disabled)
 * Max Disparity: 3040.0 (reduced for speed)
 * Confidence Threshold: 55

### Common Parameters

Most parameters are consistent across all RVC2 presets:

 * Disparity Shift: 0

 * Left-Right Check Threshold: 10 (varies: 5 for HIGH_DETAIL, FAST_ACCURACY)

 * Census Transform
   
   * Enable Mean Mode: True
   * Noise Threshold Offset: 1
   * Noise Threshold Scale: 1

 * Cost Aggregation
   
   * Division Factor: 1
   * Horizontal Penalty P1: 250
   * Horizontal Penalty P2: 500
   * Vertical Penalty P1: 250
   * Vertical Penalty P2: 500

 * Postprocessing - Brightness Filter
   
   * Min: 0
   * Max: 256

#### RVC4

### Available Presets

RVC4 supports the following presets:

 * ACCURACY: Prioritizes depth accuracy over fill-rate for precise depth measurements
 * DENSITY: Prioritizes fill-rate and processing speed for dense depth maps at higher frame rates

### Preset-Specific Differences

For details on the filters, see [Platform-Specific
Configuration](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/stereo_depth.md).

ACCURACY Preset:

 * Extended Disparity: True
 * Subpixel: True (4 bits, fixed for RVC4)
 * Software Left-Right Check: False
 * Median Filter: MEDIAN_OFF
 * Spatial Filter: enable=False
 * Speckle Filter: enable=True, speckleRange=200, differenceThreshold=2
 * Temporal Filter: enable=False
 * Decimation Filter: decimationFactor=1 (disabled), decimationMode=NON_ZERO_MEAN
 * Adaptive Median Filter: enable=True, confidenceThreshold=200
 * Hole Filling: enable=True, highConfidenceThreshold=240, fillConfidenceThreshold=251, minValidDisparity=1
 * Confidence Threshold: 97
 * Confidence Metrics:
   * Occlusion Confidence Weight: 14
   * Motion Vector Confidence Weight: 16
   * Motion Vector Confidence Threshold: 1
   * Flatness Confidence Weight: 2
   * Flatness Confidence Threshold: 4
   * Flatness Override: False
 * Census Transform: noiseThresholdOffset=0, noiseThresholdScale=84
 * Threshold Filter: minRange=0, maxRange=65535
 * Brightness Filter: minBrightness=0, maxBrightness=256

DENSITY Preset:

 * Extended Disparity: True
 * Subpixel: True (4 bits, fixed for RVC4)
 * Software Left-Right Check: True (threshold: 4)
 * Median Filter: KERNEL_5x5
 * Spatial Filter: enable=False
 * Speckle Filter: enable=True, speckleRange=200, differenceThreshold=2
 * Temporal Filter: enable=False
 * Decimation Filter: decimationFactor=1 (disabled), decimationMode=PIXEL_SKIPPING
 * Adaptive Median Filter: enable=True, confidenceThreshold=200
 * Hole Filling: enable=False
 * Confidence Threshold: 20
 * Confidence Metrics:
   * Occlusion Confidence Weight: 28
   * Motion Vector Confidence Weight: 0
   * Motion Vector Confidence Threshold: 1
   * Flatness Confidence Weight: 4
   * Flatness Confidence Threshold: 4
   * Flatness Override: False
 * Census Transform: noiseThresholdOffset=0, noiseThresholdScale=-40
 * Threshold Filter: minRange=0, maxRange=65535
 * Brightness Filter: minBrightness=-1, maxBrightness=256

### Common Parameters

Most parameters are consistent across all RVC4 presets:

 * Subpixel: 4 bits (fixed for RVC4)
 * Extended Disparity: True
 * Spatial Filter: enable=False
 * Speckle Filter: enable=True, speckleRange=200, differenceThreshold=2
 * Temporal Filter: enable=False
 * Decimation Filter: decimationFactor=1 (disabled)
 * Adaptive Median Filter: enable=True, confidenceThreshold=200
 * Threshold Filter: minRange=0, maxRange=65535

### Fixing noisy depth

A few topics we have noticed that are relevant for stereo depth quality are:

 * [Scene Texture](#Configuring%2520Stereo%2520Depth-Scene%2520Texture)
 * [Stereo depth confidence threshold](#Configuring%2520Stereo%2520Depth-Stereo%2520depth%2520confidence%2520threshold)
 * [Stereo camera pair noise](#Configuring%2520Stereo%2520Depth-Stereo%2520camera%2520pair%2520noise)
 * [Stereo postprocessing filters](#Configuring%2520Stereo%2520Depth-Stereo%2520postprocessing%2520filters)

### Scene Texture

Due to the way the stereo matching algorithm works, passive stereo depth requires to have a good texture in the scene, otherwise,
the depth will be noisy/invalid. low-visual-interest surfaces (blank surfaces with little to no texture), such as a wall or floor.

Solution: Our OAK Pro version of OAK cameras have onboard [IR laser dot
projector](https://docs.luxonis.com/hardware/platform/features/ir-perception/dot-projector.md), which projects thousands of little
dots on the scene, which helps the stereo matching algorithm as it provides more texture to the scene.

The technique that we use is called ASV ([Conventional Active Stereo
Vision](https://en.wikipedia.org/wiki/Computer_stereo_vision#Conventional_active_stereo_vision_(ASV))) as stereo matching is
performed on the device the same way as on a passive stereo OAK-D.

### Stereo depth confidence threshold

When calculating the disparity, each pixel in the disparity map gets assigned a confidence value 0..255 by the stereo matching
algorithm. This confidence score is kind of inverted (if, say, comparing with NN confidences):

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

For the final disparity map, filtering is applied based on the confidence threshold value: the pixels that have their confidence
score larger than the threshold get invalidated, i.e. their disparity value is set to zero. You can set the confidence threshold
via the API below.

This means that with the confidence threshold, users can prioritize fill-rate or accuracy.

#### Python

```python
# Create the StereoDepth node
stereo_depth = pipeline.create(dai.node.StereoDepth)
stereo_depth.initialConfig.setConfidenceThreshold(threshold)

# Or, alternatively, set the Stereo Preset Mode:
# Prioritize fill-rate, sets Confidence threshold to 245
stereo_depth.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_DENSITY)
# Prioritize accuracy, sets Confidence threshold to 200
stereo_depth.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_ACCURACY)
```

#### C++

```cpp
// Create the StereoDepth node
auto stereo_depth = pipeline.create<dai::node::StereoDepth>();
stereo_depth->initialConfig.setConfidenceThreshold(threshold);

// Or, alternatively, set the Stereo Preset Mode:
// Prioritize fill-rate, sets Confidence threshold to 245
stereo_depth->setDefaultProfilePreset(dai::node::StereoDepth::Preset::HIGH_DENSITY);
// Prioritize accuracy, sets Confidence threshold to 200
stereo_depth->setDefaultProfilePreset(dai::node::StereoDepth::Preset::HIGH_ACCURACY);
```

### Stereo camera pair noise

If input left/right images are noisy, the disparity map will be noisy as well. So the prerequisite for good depth are high IQ (see
[Image Quality](https://docs.luxonis.com/hardware/platform/sensors/image-quality.md) docs) left/right stereo images. Active stereo
(OAK Pro version of OAK cameras) mostly alleviates this issue, but for passive stereo cameras, there are a few things you can do
to improve the quality of the stereo camera pair.

It is preferred to use mono (grayscale) cameras for the stereo camera pair as they have better quantum efficiency (QE) as they
don't have color (Bayer) filter. Higher QE means more signal will be generated for the same amount of light (photons), which leads
to better SNR (signal-to-noise ratio).

For better low-light performance, it's advised to use longer exposure times instead of higher gain (ISO) as it will improve SNR.
Sometimes this means lowering camera FPS - at 30 FPS, you can use 1/30s exposure time, at 15 FPS, you can use 1/15s exposure time,
etc. For more information, see [Low-light increased
sensitivity](https://docs.luxonis.com/hardware/platform/sensors/image-quality.md).

Another potential improvement is to tweak the sensor's ISP settings, like chroma & luma denoise, and sharpness. For more
information, see the [Color camera ISP configuration](https://docs.luxonis.com/hardware/platform/sensors/image-quality.md).

### Stereo postprocessing filters

The [StereoDepth](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/stereo_depth.md) node has a few
postprocessing filters that run on-device, which can be enabled to improve the quality of the disparity map. For implementation
(API) details, see [StereoDepth configurable
blocks](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/stereo_depth.md).

As these filters run on the device, it has a some performance cost, which means that at high-resolution frames (1MP) these might
bottleneck the FPS. To improve the cost, one should consider using lower-resolution frames (eg. 400P) and/or using [Decimation
filter](#Configuring%2520Stereo%2520Depth-Decimation%2520filter). Due to additional processing, these filters also introduce
[additional latency](https://docs.luxonis.com/software-v3/depthai/tutorials/optimizing.md).

> If the pipeline complains about shave/memory allocation, try increasing the HW resources used in postprocessing with
> `setPostProcessingHardwareResources(n_shaves, n_cmx)`
> -->
> `stereoDepth.setPostProcessingHardwareResources(3, 3)`
> .

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

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

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

#### 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/).

#### 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. When there's no
available pixel, StereoDepth node will set that area to 0 (black) by default, but can be changed with
stereoDepth.setRectifyEdgeFillColor(int8). This black area can then be invalidated with brightness filter, as seen below:

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

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

It's also very useful [for pointclouds](#Configuring%2520Stereo%2520Depth-Decimation%2520filter%2520for%2520pointcloud).

#### 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 and can be set via

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

### Improving depth accuracy

The above chapter we focused on noise, which isn't necessarily the only reason for inaccurate depth.

There are a few ways to improve depth accuracy:

 * (mentioned above) [Fixing noisy depth](#Fixing%20noisy%20depth) - depth should be high quality in order to be accurate
 * (mentioned above) [Stereo depth confidence
   threshold](#Configuring%2520Stereo%2520Depth-Stereo%2520depth%2520confidence%2520threshold) should be low(er) in order to get
   the best accuracy
 * Enable [Stereo Subpixel mode](#Configuring%2520Stereo%2520Depth-Stereo%2520Subpixel%2520mode), especially if the object/scene
   isn't close to MinZ of the camera

### Stereo Subpixel mode

Let's first start with what Stereo Subpixel mode is and how it works. For image subpixel explanation, see [What's
subpixel?](https://dsp.stackexchange.com/questions/34103/subpixel-what-is-it).

> The stereo depth pipeline is very complex (see
> [Internal block diagram of StereoDepth
node](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/stereo_depth.md)
> ), and we will simplify it here for better understanding. It actually doesn't use confidence (eg.
> `stereoDepth.confidenceMap`
> output), but cost dump, which is what is used to calculate confidence values.

When calculating disparity depth, stereo matching algorithm assigns a "confidence" score for each disparity pixel, which means
each pixel of the depth image contains 96 bytes (for confidence). If you are interested in all these cost values, you can use
stereoDepth.debugDispCostDump output, just note it's a very large output (eg. 1280*800*96 => 98MB for each frame).

Stereo Subpixel mode will calculate subpixel disparity by looking at the confidence values of the 2 neighboring disparity pixels
in each direction. In the above example graph, in normal mode, StereoDepth would just get the max disparity = 34 pixels, but in
Subpixel mode, it will return a bit more, eg. 34.375 pixels, as confidences for pixels 35 and 36 are quite high as well.

TL;DR: Stereo Subpixel mode should always provide more accurate depth, but will consume additional HW resources (see [Stereo depth
FPS](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/stereo_depth.md) for impact).

#### Stereo subpixel effect on layering

Default stereo depth output has 0..95 disparity pixels, which would produce 96 unique depth values. This can especially be seen
when using pointcloud representation and seeing how there are discrete "layers" of points, instead of a smooth transition:

This layering can especially be seen at longer distances, where these layers are exponentially further apart.

But with Stereo Subpixel mode enabled, there are many more unique values possible, which produces more granular depth steps, and
thus smoother a pointcloud.

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

One can change the number of subpixel bits by setting stereoDepth.setSubpixelFractionalBits(int) parameter to 3, 4 or 5 bits.

### Short range stereo depth

To get accurate short-range depth, you'd first need to follow [Improving depth accuracy](#Improving%20depth%20accuracy) steps. For
most normal-FOV, OV9282 OAK-D* cameras, you'd want to have the object/scene about 70cm away from the camera, where you'd get below
2% error (with good [Scene Texture](#Configuring%2520Stereo%2520Depth-Scene%2520Texture)), so ± 1.5cm error.

But how to get an even better depth accuracy, eg. sub-cm stereo depth accuracy? As we have learned at [How baseline distance and
focal length affect
depth](#Configuring%2520Stereo%2520Depth-How%2520baseline%2520distance%2520and%2520focal%2520length%2520affect%2520depth), we
would want to have a closer baseline distance and/or narrower FOV lenses.

That's why for the short-range depth perception we suggest using the [OAK-D
SR](https://docs.luxonis.com/hardware/products/OAK-D%2520SR.md) or the [OAK-D
ToF](https://docs.luxonis.com/hardware/products/OAK-D%2520ToF.md), as they have 2 cm baseline distance, 800P resolution, and is
ideal for depth sensing of up to 1 meter.

Going back to [Depth from disparity](#Configuring%2520Stereo%2520Depth-Depth%2520from%2520disparity), minimal depth perception
(MinZ) is defined by the following formula, where the disparity is 95 pixels (maximum number of pixel for disparity search):

### How to get lower MinZ

If the depth results for close-in objects look weird, this is likely because they are below MinZ distance of the OAK camera. You
can get lower MinZ for OAK cameras by either:

 * [Lowering resolution](#Configuring%2520Stereo%2520Depth-Lowering%2520resolution%2520to%2520decrease%2520MinZ)
 * Enabling [Stereo Extended Disparity mode](#Configuring%2520Stereo%2520Depth-Stereo%2520Extended%2520Disparity%2520mode)
 * Enabling [Stereo companding mode](#Configuring%2520Stereo%2520Depth-Stereo%2520companding%2520mode)
 * Using [Disparity shift](#Configuring%2520Stereo%2520Depth-Disparity%2520shift) - suggested in a controlled environment, where
   MaxZ is known

Both of the last 2 options can be enabled at the same time, which would set the minimum depth to 1/4 of the standard settings, but
at such short distances the MinZ could be limited by the focal length.

#### Lowering resolution to decrease MinZ

Above we have a formula for MinZ, and by lowering the resolution, we are lowering focal length (in pixels), so let's look at the
formula again:

As you can see, by lowering resolution by 2, we are also lowering MinZ by 2. Note that because you have fewer pixels, you will
also have lower depth accuracy (in cm).

#### Stereo Extended Disparity mode

Very similar to [Lowering resolution to decrease
MinZ](#Configuring%2520Stereo%2520Depth-Lowering%2520resolution%2520to%2520decrease%2520MinZ), Extended mode runs stereo depth
pipeline twice (thus consuming more HW resources); once with resolution of the frame that was passed to
[StereoDepth](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/stereo_depth.md) node, and once with
resolution downscaled by 2, then combines the 2 output disparity maps.

#### Stereo companding mode

Disparity companding does sparse disparity matching:

 * First 48 pixels it does pixel by pixel matching, meaning at longer range there's no downside
 * Next 32 pixels it does matching every 2nd pixel, so accuracy is halved (at closer range)
 * Last 16 pixel it does matching every 4th pixel, so accuracy is quartered (at closest range). Because accuracy is the best at
   closest range anyways, this is can be a good tradeoff.

Compared to extended mode, compading mode is faster, as it doesn't perform disparity matching twice. Note that companding mode
doesn't work with extended mode.

[Google Sheets here](https://docs.google.com/spreadsheets/d/1N_glGDBCTkgbjEN0IUja5JQJrr-OLoaLbt6P-34u0hk/edit?usp=sharing) for the
above graph. Note that this graph is for full-pixel disparity, when enabling subpixel mode the accuracy will be better (see
[Stereo depth accuracy docs](https://docs.luxonis.com/hardware/platform/depth/depth-accuracy.md)).

```python
stereo = pipeline.create(dai.node.StereoDepth)
cfg = stereo.initialConfig.get()
# Enable companding mode
cfg.costMatching.enableCompanding = True
stereo.initialConfig.set(cfg)
```

#### Disparity shift

In a controlled environment, where MaxZ is known in advance, to perceive closer depth range it's advised to use disparity shift,
as it doesn't decrease depth accuracy as the other 2 methods above do.

Disparity shift will shift the starting point of the disparity search, which will significantly decrease MaxZ, but it will also
decrease the MinZ. Disparity shift can be combined with extended/subpixel/LR-check modes.

The Left graph shows min and max disparity and depth for [OAK-D](https://docs.luxonis.com/hardware/products/OAK-D.md) (7.5cm
baseline, 800P resolution, ~70° HFOV) by default (disparity shift=0). See [Depth from
disparity](#Configuring%2520Stereo%2520Depth-Depth%2520from%2520disparity). Since hardware (stereo block) has a fixed 95 pixel
disparity search, DepthAI will search from 0 pixels (depth=INF) to 95 pixels (depth=71cm).

Limitations: The 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). This also means that depth will be very accurate at the short range
(theoretically below 5mm depth error).

 * 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.
 * The tradeoff in reducing the MinZ this way is that objects at distances farther away than MaxZ will not be seen.
 * 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.
 * 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.

Compared to Extended disparity, disparity shift:

 * (+) Is faster, as it doesn't require an extra computation, which means there's also no extra latency
 * (-) Reduces the MaxZ (significantly), while extended disparity only reduces MinZ.

Disparity shift can be combined with extended disparity.

### setDisparityShift(self, arg0: typing.SupportsInt) -> StereoDepthConfig: StereoDepthConfig

Kind: Method

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.

### Close range depth limitations

Since depth is calculated from disparity, which requires the pixels to overlap, there is inherently a vertical band on the left
side of the left mono camera and on the right side of the right mono camera, where depth can not be calculated, since it is seen
by only 1 stereo camera. That band is marked with B on the following picture.

At very close distance, even when enabling [Stereo Extended Disparity
mode](#Configuring%2520Stereo%2520Depth-Stereo%2520Extended%2520Disparity%2520mode) and [Lowering
resolution](#Configuring%2520Stereo%2520Depth-Lowering%2520resolution%2520to%2520decrease%2520MinZ), you will notice this vertical
band of invalid depth pixel.

Meaning of variables on the picture:

 * BL [cm] - Baseline of stereo cameras.
 * Dv [cm] - Minimum distance where both cameras see an object (thus where depth can be calculated).
 * B [pixels] - Width of the band where depth cannot be calculated.
 * W [pixels] - Width of mono in pixels camera or amount of horizontal pixels, also noted as HPixels in other formulas.
 * D [cm] - Distance from the camera plane to an object (see image [Measuring real-world object
   dimensions](#Configuring%2520Stereo%2520Depth-Measuring%2520real-world%2520object%2520dimensions)).
 * F [cm] - Width of image at the distance D.

With the use of the tan function, the following formulas can be obtained:

 * F = 2 * D * tan(HFOV/2)
 * Dv = (BL/2) * tan(90 - HFOV/2)

In order to obtain B, we can use tan function again (same as for F), but this time we must also multiply it by the ratio between W
and F in order to convert units to pixels. That gives the following formula:

Example: If we are using OAK-D, which has a HFOV of 72°, a baseline (BL) of 7.5 cm and 640x400 (400P) resolution is used,
therefore W = 640 and an object is D = 100 cm away, we can calculate B in the following way:

```bash
Dv = 7.5 / 2 * tan(90 - 72/2) = 3.75 * tan(54°) = 5.16 cm
B = 640 * 5.16 / 100 = 33 # pixels
```

Credit for calculations and images goes to our community member gregflurry, which he made on
[this](https://discuss.luxonis.com/d/339-naive-question-regarding-stereodepth-disparity-and-depth-outputs/7) forum post.

### Measuring real-world object dimensions

Because the depth map contains the Z distance, objects in parallel with the camera are measured accurately standard. For objects
not in parallel, the Euclidean distance calculation can be used. Please refer to the below:

When running eg. the [RGB & Yolo with spatial
data](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/detection_network.md) example, you could calculate the
distance to the detected object from XYZ coordinates
([SpatialImgDetections](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/spatial_img_detections.md)) using
the code below (after code line 143 of the example):

```python
distance = math.sqrt(detection.spatialCoordinates.x ** 2 + detection.spatialCoordinates.y ** 2 + detection.spatialCoordinates.z ** 2) # mm
```

### Long range stereo depth

To get accurate long-range depth, we should first check [Improving depth accuracy](#Improving%20depth%20accuracy) steps, as they
are especially applicable to long-range depth.

For long-range depth, we should also consider the following:

 * Narrow FOV lenses
 * Wide baseline distance between stereo cameras

That's why for long range, we suggest using [OAK-D Long Range](https://docs.luxonis.com/hardware/products/OAK-D%2520LR.md), which
has a (larger) baseline distance of 15cm and default FOV of 60°. It has [M12 mount
lenses](https://docs.luxonis.com/hardware.md#m12-selectable-fov), so users can replace these with even narrower (or wider) FOV
lenses.

### Fixing noisy pointcloud

For noisy pointcloud we suggest a few approaches:

 * (mentioned above) Start with the [Fixing noisy depth](#Fixing%20noisy%20depth) chapter, as otherwise, noise will produce points
   all over the pointcloud
 * (mentioned above) Continue with the [Improving depth accuracy](#Improving%20depth%20accuracy) chapter - depth inaccuracy will
   be easily visible in pointcloud
   * Enable Stereo subpixel mode, especially due to the [Stereo subpixel effect on
     layering](#Configuring%2520Stereo%2520Depth-Stereo%2520subpixel%2520effect%2520on%2520layering)
 * [Decimation filter for pointcloud](#Configuring%2520Stereo%2520Depth-Decimation%2520filter%2520for%2520pointcloud) for faster
   processing (FPS) and additional filtering
 * [Invalidating pixels around the
   corner](#Configuring%2520Stereo%2520Depth-Invalidating%2520pixels%2520around%2520the%2520corner) should help to reduce noise
   around the corners of the depth frame
 * [Host-side pointcloud filtering](#Configuring%2520Stereo%2520Depth-Host-side%2520pointcloud%2520filtering) for additional
   filtering

### Decimation filter for pointcloud

[Decimation filter](#Configuring%2520Stereo%2520Depth-Decimation%2520filter) is especially useful for pointclouds, you don't
really want 1 million points (even though it sounds good for marketing), as it's too much data to process. Decimation filter helps
here, and should be enabled when working with pointclouds.

When using decimation filter for pointcloud you should enable median/mean mode decimation, as it will provide additional filtering
(compared to pixel skipping mode). It also makes other [Stereo postprocessing
filters](#Configuring%2520Stereo%2520Depth-Stereo%2520postprocessing%2520filters) faster, since there will be less data to
process.

### Invalidating pixels around the corner

There are often invalid/noisy pixels around the corners, and we have seen that some customers preventively invalidate a few pixels
(eg. 3) all around the corner of depth image. We also suggest enabling [Brightness
filter](#Configuring%2520Stereo%2520Depth-Brightness%2520filter), especially due to rectification "artifacts".

### Host-side pointcloud filtering

Besides device-side [Stereo postprocessing filters](#Configuring%2520Stereo%2520Depth-Stereo%2520postprocessing%2520filters), we
also suggest running host-side pointcloud filtering (with eg. [Open3D](https://www.open3d.org/), or
[PCL](https://pointclouds.org/) library).

We especially suggest using pointcloud voxalization and removing statistical outliers techniques, [example
here](https://github.com/luxonis/oak-examples/blob/master/gen2-box_measurement/projector_3d.py#L35-L38) for both of these.
