Class StereoDepthConfig

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class StereoDepthConfig : public dai::Buffer

StereoDepthConfig message.

Public Types

using MedianFilter = filters::params::MedianFilter

Public Functions

StereoDepthConfig() = default

Construct StereoDepthConfig message.

virtual ~StereoDepthConfig()
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

bool getLeftRightCheck() const

Get left-right check setting

StereoDepthConfig &setExtendedDisparity(bool enable)

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

bool getExtendedDisparity() const

Get extended disparity setting

StereoDepthConfig &setSubpixel(bool enable)

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

Suitable for long range. Currently incompatible with extended disparity

bool getSubpixel() const

Get subpixel setting

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.

int getSubpixelFractionalBits() const

Get number of fractional bits for subpixel mode

StereoDepthConfig &setDepthUnit(AlgorithmControl::DepthUnit depthUnit)

Set depth unit of depth map.

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

AlgorithmControl::DepthUnit getDepthUnit()

Get depth unit of depth map.

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.

StereoDepthConfig &setFiltersComputeBackend(dai::ProcessorType filtersBackend)

Set filters compute backend

dai::ProcessorType getFiltersComputeBackend() const

Get filters compute backend

float getMaxDisparity() const

Useful for normalization of the disparity map.

Returns:

Maximum disparity value that the node can return

virtual void serialize(std::vector<std::uint8_t> &metadata, DatatypeEnum &datatype) const override
DEPTHAI_SERIALIZE(StereoDepthConfig, algorithmControl, postProcessing, censusTransform, costMatching, costAggregation, confidenceMetrics, filtersBackend)

Public Members

AlgorithmControl algorithmControl

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

PostProcessing postProcessing

Controls the postprocessing of disparity and/or depth map.

CensusTransform censusTransform

Census transform settings.

CostMatching costMatching

Cost matching settings.

CostAggregation costAggregation

Cost aggregation settings.

ConfidenceMetrics confidenceMetrics

Confidence metrics settings.

dai::ProcessorType filtersBackend = dai::ProcessorType::CPU
struct AlgorithmControl

Public Types

enum class DepthAlign : int32_t

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

Values:

enumerator RECTIFIED_RIGHT
enumerator RECTIFIED_LEFT
enumerator CENTER
enum class DepthUnit : int32_t

Measurement unit for depth data

Values:

enumerator METER
enumerator CENTIMETER
enumerator MILLIMETER
enumerator INCH
enumerator FOOT
enumerator CUSTOM

Public Members

DepthAlign depthAlign = DepthAlign::RECTIFIED_LEFT

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

DepthUnit depthUnit = DepthUnit::MILLIMETER

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

float customDepthUnitMultiplier = 1000.f

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 = true

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

bool enableSwLeftRightCheck = false

Enables software left right check. Applicable to RVC4 only.

bool enableExtended = false

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

bool enableSubpixel = true

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

std::int32_t leftRightCheckThreshold = 10

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 = 5

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 = 0

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
std::int32_t numInvalidateEdgePixels = 0

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.

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

Public Types

enum class KernelSize : std::int32_t

Census transform kernel size possible values.

Values:

enumerator AUTO
enumerator KERNEL_5x5
enumerator KERNEL_7x7
enumerator KERNEL_7x9

Public Members

KernelSize kernelSize = KernelSize::AUTO

Census transform kernel size.

uint64_t kernelMask = 0

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 = true

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

uint32_t threshold = 0

Census transform comparison threshold value.

int8_t noiseThresholdOffset = 1

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 = 1

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

struct ConfidenceMetrics

Public Members

uint8_t occlusionConfidenceWeight = 20

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

uint8_t motionVectorConfidenceWeight = 4

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

uint8_t motionVectorConfidenceThreshold = 1

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

uint8_t flatnessConfidenceWeight = 8

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

uint8_t flatnessConfidenceThreshold = 2

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

bool flatnessOverride = false

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

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

Public Members

uint8_t divisionFactor = 1

Cost calculation linear equation parameters.

uint16_t horizontalPenaltyCostP1 = defaultPenaltyP1

Horizontal P1 penalty cost parameter.

uint16_t horizontalPenaltyCostP2 = defaultPenaltyP2

Horizontal P2 penalty cost parameter.

uint16_t verticalPenaltyCostP1 = defaultPenaltyP1

Vertical P1 penalty cost parameter.

uint16_t verticalPenaltyCostP2 = defaultPenaltyP2

Vertical P2 penalty cost parameter.

P1Config p1Config
P2Config p2Config

Public Static Attributes

static constexpr const int defaultPenaltyP1 = 250
static constexpr const int defaultPenaltyP2 = 500
struct P1Config

Structure for adaptive P1 penalty configuration.

Public Members

bool enableAdaptive = true

Used to disable/enable adaptive penalty.

uint8_t defaultValue = 11

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 = 10

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 = 22

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 = 15

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 = 5

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

struct P2Config

Structure for adaptive P2 penalty configuration.

Public Functions

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

Public Members

bool enableAdaptive = true

Used to disable/enable adaptive penalty.

uint8_t defaultValue = 33

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 = 22

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 = 63

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

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

Public Types

enum class DisparityWidth : std::uint32_t

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

Values:

enumerator DISPARITY_64
enumerator DISPARITY_96

Public Members

DisparityWidth disparityWidth = DisparityWidth::DISPARITY_96

Disparity search range, default 96 pixels.

bool enableCompanding = false

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 = 0

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

uint8_t confidenceThreshold = 55

Disparities with confidence value over this threshold are accepted.

bool enableSwConfidenceThresholding = false

Enable software confidence thresholding. Applicable to RVC4 only.

LinearEquationParameters linearEquationParameters

Cost calculation linear equation parameters.

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

Public Functions

DEPTHAI_SERIALIZE(LinearEquationParameters, alpha, beta, threshold)

Public Members

uint8_t alpha = 0
uint8_t beta = 2
uint8_t threshold = 127
struct PostProcessing

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

Public Types

enum class Filter : int32_t

Values:

enumerator NONE
enumerator DECIMATION
enumerator SPECKLE
enumerator MEDIAN
enumerator SPATIAL
enumerator TEMPORAL
enumerator FILTER_COUNT
using SpatialFilter = filters::params::SpatialFilter
using TemporalFilter = filters::params::TemporalFilter
using SpeckleFilter = filters::params::SpeckleFilter

Public Members

std::array<Filter, 5> filteringOrder = {Filter::MEDIAN, Filter::DECIMATION, Filter::SPECKLE, Filter::SPATIAL, Filter::TEMPORAL}

Order of filters to be applied if filtering is enabled.

MedianFilter median = MedianFilter::MEDIAN_OFF

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

std::int16_t bilateralSigmaValue = 0

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

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

TemporalFilter temporalFilter

Temporal filtering with optional persistence.

ThresholdFilter thresholdFilter

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

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

SpeckleFilter speckleFilter

Speckle filtering. Removes speckle noise.

DecimationFilter decimationFilter

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

HoleFilling holeFilling
AdaptiveMedianFilter adaptiveMedianFilter
struct AdaptiveMedianFilter

Public Functions

DEPTHAI_SERIALIZE(AdaptiveMedianFilter, enable, confidenceThreshold)

Public Members

bool enable = true

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

uint8_t confidenceThreshold = 200

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

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

Public Functions

DEPTHAI_SERIALIZE(BrightnessFilter, minBrightness, maxBrightness)

Public Members

std::int32_t minBrightness = 0

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

std::int32_t maxBrightness = 256

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

struct DecimationFilter

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

Public Types

enum class DecimationMode : int32_t

Decimation algorithm type.

Values:

enumerator PIXEL_SKIPPING
enumerator NON_ZERO_MEDIAN
enumerator NON_ZERO_MEAN

Public Functions

DEPTHAI_SERIALIZE(DecimationFilter, decimationFactor, decimationMode)

Public Members

std::uint32_t decimationFactor = 1

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

DecimationMode decimationMode = DecimationMode::PIXEL_SKIPPING

Decimation algorithm type.

struct HoleFilling

Public Members

bool enable = true

Flag to enable post-processing hole-filling.

uint8_t highConfidenceThreshold = 210

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

uint8_t fillConfidenceThreshold = 200

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 = 1

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 = true

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

struct ThresholdFilter

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

Public Functions

DEPTHAI_SERIALIZE(ThresholdFilter, minRange, maxRange)

Public Members

std::int32_t minRange = 0

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

std::int32_t maxRange = 65535

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