StereoDepthConfig

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

Examples of functionality

Reference

class depthai.StereoDepthConfig

StereoDepthConfig message.

class CensusTransform

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

class KernelSize

Census transform kernel size possible values.

Members:

AUTO :

KERNEL_5x5 :

KERNEL_7x7 :

KERNEL_7x9 :

property name
property enableMeanMode

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

property kernelMask

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.

property kernelSize

Census transform kernel size.

property threshold

Census transform comparison threshold value.

class CostAggregation

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.

property divisionFactor

Cost calculation linear equation parameters.

property horizontalPenaltyCostP1

Horizontal P1 penalty cost parameter.

property horizontalPenaltyCostP2

Horizontal P2 penalty cost parameter.

property verticalPenaltyCostP1

Vertical P1 penalty cost parameter.

property verticalPenaltyCostP2

Vertical P2 penalty cost parameter.

class CostMatching

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.

class DisparityWidth

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

Members:

DISPARITY_64 :

DISPARITY_96 :

property name
class LinearEquationParameters

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.

property confidenceThreshold

Disparities with confidence value under this threshold are accepted. Higher confidence threshold means disparities with less confidence are accepted too.

property disparityWidth

Disparity search range, default 96 pixels.

property enableCompanding

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.

property invalidDisparityValue

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

property linearEquationParameters

Cost calculation linear equation parameters.

class MedianFilter

Median filter config

Members:

MEDIAN_OFF

KERNEL_3x3

KERNEL_5x5

KERNEL_7x7

property name
class PostProcessing

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

class BrightnessFilter

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.

property maxBrightness

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

property minBrightness

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

class DecimationFilter

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

class DecimationMode

Decimation algorithm type.

Members:

PIXEL_SKIPPING :

NON_ZERO_MEDIAN :

NON_ZERO_MEAN :

property name
property decimationFactor

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

property decimationMode

Decimation algorithm type.

class SpatialFilter

1D edge-preserving spatial filter using high-order domain transform.

property alpha

The Alpha factor in an exponential moving average with Alpha=1 - no filter. Alpha = 0 - infinite filter. Determines the amount of smoothing.

property delta

Step-size boundary. Establishes the threshold used to preserve “edges”. If the disparity value between neighboring pixels exceed the disparity threshold set by this delta parameter, then filtering will be temporarily disabled. Default value 0 means auto: 3 disparity integer levels. In case of subpixel mode it’s 3*number of subpixel levels.

property enable

Whether to enable or disable the filter.

property holeFillingRadius

An in-place heuristic symmetric hole-filling mode applied horizontally during the filter passes. Intended to rectify minor artefacts with minimal performance impact. Search radius for hole filling.

property numIterations

Number of iterations over the image in both horizontal and vertical direction.

class SpeckleFilter

Speckle filtering. Removes speckle noise.

property enable

Whether to enable or disable the filter.

property speckleRange

Speckle search range.

class TemporalFilter

Temporal filtering with optional persistence.

class PersistencyMode

Persistency algorithm type.

Members:

PERSISTENCY_OFF :

VALID_8_OUT_OF_8 :

VALID_2_IN_LAST_3 :

VALID_2_IN_LAST_4 :

VALID_2_OUT_OF_8 :

VALID_1_IN_LAST_2 :

VALID_1_IN_LAST_5 :

VALID_1_IN_LAST_8 :

PERSISTENCY_INDEFINITELY :

property name
property alpha

The Alpha factor in an exponential moving average with Alpha=1 - no filter. Alpha = 0 - infinite filter. Determines the extent of the temporal history that should be averaged.

property delta

Step-size boundary. Establishes the threshold used to preserve surfaces (edges). If the disparity value between neighboring pixels exceed the disparity threshold set by this delta parameter, then filtering will be temporarily disabled. Default value 0 means auto: 3 disparity integer levels. In case of subpixel mode it’s 3*number of subpixel levels.

property enable

Whether to enable or disable the filter.

property persistencyMode

Persistency mode. If the current disparity/depth value is invalid, it will be replaced by an older value, based on persistency mode.

class ThresholdFilter

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

property maxRange

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

property minRange

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

property bilateralSigmaValue

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.

property brightnessFilter

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.

property decimationFilter

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

property median

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

property spatialFilter

This type of filter will smooth the depth noise while attempting to preserve edges.

Type

Edge-preserving filtering

property speckleFilter

Speckle filtering. Removes speckle noise.

property temporalFilter

Temporal filtering with optional persistence.

property thresholdFilter

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

get(self: depthai.StereoDepthConfig)depthai.RawStereoDepthConfig

Retrieve configuration data for StereoDepth.

Returns

config for stereo depth algorithm

getBilateralFilterSigma(self: depthai.StereoDepthConfig)int

Get sigma value for 5x5 bilateral filter

getConfidenceThreshold(self: depthai.StereoDepthConfig)int

Get confidence threshold for disparity calculation

getData(self: object) → numpy.ndarray[numpy.uint8]

Get non-owning reference to internal buffer

Returns

Reference to internal buffer

getDepthUnit(self: depthai.StereoDepthConfig)depthai.RawStereoDepthConfig.AlgorithmControl.DepthUnit

Get depth unit of depth map.

getLeftRightCheckThreshold(self: depthai.StereoDepthConfig)int

Get threshold for left-right check combine

getMaxDisparity(self: depthai.StereoDepthConfig)float

Useful for normalization of the disparity map.

Returns

Maximum disparity value that the node can return

getMedianFilter(self: depthai.StereoDepthConfig)depthai.MedianFilter

Get median filter setting

getRaw(self: depthai.ADatatype)depthai.RawBuffer
getSequenceNum(self: depthai.Buffer)int

Retrieves sequence number

getTimestamp(self: depthai.Buffer)datetime.timedelta

Retrieves timestamp related to dai::Clock::now()

getTimestampDevice(self: depthai.Buffer)datetime.timedelta

Retrieves timestamp directly captured from device’s monotonic clock, not synchronized to host time. Used mostly for debugging

set(self: depthai.StereoDepthConfig, config: depthai.RawStereoDepthConfig)depthai.StereoDepthConfig

Set explicit configuration.

Parameter config:

Explicit configuration

setBilateralFilterSigma(self: depthai.StereoDepthConfig, sigma: int)depthai.StereoDepthConfig

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.

Parameter sigma:

Set sigma value for 5x5 bilateral filter. 0..65535

setConfidenceThreshold(self: depthai.StereoDepthConfig, confThr: int)depthai.StereoDepthConfig

Confidence threshold for disparity calculation

Parameter confThr:

Confidence threshold value 0..255

setData(*args, **kwargs)

Overloaded function.

  1. setData(self: depthai.Buffer, arg0: List[int]) -> None

Parameter data:

Copies data to internal buffer

  1. setData(self: depthai.Buffer, arg0: numpy.ndarray[numpy.uint8]) -> None

Parameter data:

Copies data to internal buffer

setDepthAlign(self: depthai.StereoDepthConfig, align: depthai.RawStereoDepthConfig.AlgorithmControl.DepthAlign)depthai.StereoDepthConfig
Parameter align:

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

setDepthUnit(self: depthai.StereoDepthConfig, arg0: depthai.RawStereoDepthConfig.AlgorithmControl.DepthUnit)depthai.StereoDepthConfig

Set depth unit of depth map.

Meter, centimeter, millimeter, inch, foot or custom unit is available.

setDisparityShift(self: depthai.StereoDepthConfig, arg0: int)depthai.StereoDepthConfig

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.

setExtendedDisparity(self: depthai.StereoDepthConfig, enable: bool)depthai.StereoDepthConfig

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

setLeftRightCheck(self: depthai.StereoDepthConfig, enable: bool)depthai.StereoDepthConfig

Computes and combines disparities in both L-R and R-L directions, and combine them.

For better occlusion handling, discarding invalid disparity values

setLeftRightCheckThreshold(self: depthai.StereoDepthConfig, sigma: int)depthai.StereoDepthConfig
Parameter threshold:

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

setMedianFilter(self: depthai.StereoDepthConfig, median: depthai.MedianFilter)depthai.StereoDepthConfig
Parameter median:

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

setNumInvalidateEdgePixels(self: depthai.StereoDepthConfig, arg0: int)depthai.StereoDepthConfig

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.

setSequenceNum(self: depthai.Buffer, arg0: int)depthai.Buffer

Retrieves sequence number

setSubpixel(self: depthai.StereoDepthConfig, enable: bool)depthai.StereoDepthConfig

Computes disparity with sub-pixel interpolation (3 fractional bits by default).

Suitable for long range. Currently incompatible with extended disparity

setSubpixelFractionalBits(self: depthai.StereoDepthConfig, subpixelFractionalBits: int)depthai.StereoDepthConfig

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.

setTimestamp(self: depthai.Buffer, arg0: datetime.timedelta)depthai.Buffer

Sets timestamp related to dai::Clock::now()

setTimestampDevice(self: depthai.Buffer, arg0: datetime.timedelta)depthai.Buffer

Sets timestamp related to dai::Clock::now()

class dai::StereoDepthConfig : public dai::Buffer

StereoDepthConfig message.

Public Types

using MedianFilter = dai::MedianFilter
using AlgorithmControl = RawStereoDepthConfig::AlgorithmControl
using PostProcessing = RawStereoDepthConfig::PostProcessing
using CensusTransform = RawStereoDepthConfig::CensusTransform
using CostMatching = RawStereoDepthConfig::CostMatching
using CostAggregation = RawStereoDepthConfig::CostAggregation

Public Functions

StereoDepthConfig()

Construct StereoDepthConfig message.

StereoDepthConfig(std::shared_ptr<RawStereoDepthConfig> ptr)
~StereoDepthConfig() = default
StereoDepthConfig &setDepthAlign(AlgorithmControl::DepthAlign align)

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)

Confidence threshold for disparity calculation

Parameters
  • confThr: Confidence threshold value 0..255

int getConfidenceThreshold() const

Get confidence threshold for disparity calculation

StereoDepthConfig &setMedianFilter(MedianFilter median)

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

MedianFilter getMedianFilter() const

Get median filter setting

StereoDepthConfig &setBilateralFilterSigma(uint16_t sigma)

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() const

Get sigma value for 5x5 bilateral filter

StereoDepthConfig &setLeftRightCheckThreshold(int threshold)

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

int getLeftRightCheckThreshold() const

Get threshold for left-right check combine

StereoDepthConfig &setLeftRightCheck(bool enable)

Computes and combines disparities in both L-R and R-L directions, and combine them.

For better occlusion handling, discarding invalid disparity values

StereoDepthConfig &setExtendedDisparity(bool enable)

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

StereoDepthConfig &setSubpixel(bool enable)

Computes disparity with sub-pixel interpolation (3 fractional bits by default).

Suitable for long range. Currently incompatible with extended disparity

StereoDepthConfig &setSubpixelFractionalBits(int subpixelFractionalBits)

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.

StereoDepthConfig &setDepthUnit(AlgorithmControl::DepthUnit depthUnit)

Set depth unit of depth map.

Meter, centimeter, millimeter, inch, foot or custom unit is available.

StereoDepthConfig &setDisparityShift(int disparityShift)

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)

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.

AlgorithmControl::DepthUnit getDepthUnit()

Get depth unit of depth map.

float getMaxDisparity() const

Useful for normalization of the disparity map.

Return

Maximum disparity value that the node can return

StereoDepthConfig &set(dai::RawStereoDepthConfig config)

Set explicit configuration.

Parameters
  • config: Explicit configuration

dai::RawStereoDepthConfig get() const

Retrieve configuration data for StereoDepth.

Return

config for stereo depth algorithm

Private Functions

std::shared_ptr<RawBuffer> serialize() const override

Private Members

RawStereoDepthConfig &cfg

Got questions?

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