# StereoDepthConfig

This message is used to configure the
[StereoDepth](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/stereo_depth.md) node. With this message you
can set filters, confidences, thresholds and mode of the
[StereoDepth](https://docs.luxonis.com/software-v3/depthai/depthai-components/nodes/stereo_depth.md) node.

## Examples of functionality

 * [Stereo Depth from host](https://docs.luxonis.com/software-v3/depthai/examples/stereo_depth/stereo_depth_from_host.md)

## Reference

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