Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
dai::StereoDepthConfig Class Reference

#include <StereoDepthConfig.hpp>

Inheritance diagram for dai::StereoDepthConfig:
Inheritance graph
[legend]

Public Types

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

Public Member Functions

dai::RawStereoDepthConfig get () const
 
uint16_t getBilateralFilterSigma () const
 
int getConfidenceThreshold () const
 
AlgorithmControl::DepthUnit getDepthUnit ()
 
int getLeftRightCheckThreshold () const
 
float getMaxDisparity () const
 
MedianFilter getMedianFilter () const
 
StereoDepthConfigset (dai::RawStereoDepthConfig config)
 
StereoDepthConfigsetBilateralFilterSigma (uint16_t sigma)
 
StereoDepthConfigsetConfidenceThreshold (int confThr)
 
StereoDepthConfigsetDepthAlign (AlgorithmControl::DepthAlign align)
 
StereoDepthConfigsetDepthUnit (AlgorithmControl::DepthUnit depthUnit)
 
StereoDepthConfigsetDisparityShift (int disparityShift)
 
StereoDepthConfigsetExtendedDisparity (bool enable)
 
StereoDepthConfigsetLeftRightCheck (bool enable)
 
StereoDepthConfigsetLeftRightCheckThreshold (int threshold)
 
StereoDepthConfigsetMedianFilter (MedianFilter median)
 
StereoDepthConfigsetNumInvalidateEdgePixels (int32_t numInvalidateEdgePixels)
 
StereoDepthConfigsetSubpixel (bool enable)
 
StereoDepthConfigsetSubpixelFractionalBits (int subpixelFractionalBits)
 
 StereoDepthConfig ()
 
 StereoDepthConfig (std::shared_ptr< RawStereoDepthConfig > ptr)
 
virtual ~StereoDepthConfig ()=default
 
- Public Member Functions inherited from dai::Buffer
 Buffer ()
 Creates Buffer message. More...
 
 Buffer (std::shared_ptr< dai::RawBuffer > ptr)
 
std::vector< std::uint8_t > & getData () const
 Get non-owning reference to internal buffer. More...
 
int64_t getSequenceNum () const
 
std::chrono::time_point< std::chrono::steady_clock, std::chrono::steady_clock::duration > getTimestamp () const
 
std::chrono::time_point< std::chrono::steady_clock, std::chrono::steady_clock::duration > getTimestampDevice () const
 
void setData (const std::vector< std::uint8_t > &data)
 
void setData (std::vector< std::uint8_t > &&data)
 
BuffersetSequenceNum (int64_t sequenceNum)
 
BuffersetTimestamp (std::chrono::time_point< std::chrono::steady_clock, std::chrono::steady_clock::duration > timestamp)
 
BuffersetTimestampDevice (std::chrono::time_point< std::chrono::steady_clock, std::chrono::steady_clock::duration > timestamp)
 
virtual ~Buffer ()=default
 
- Public Member Functions inherited from dai::ADatatype
 ADatatype (std::shared_ptr< RawBuffer > r)
 
std::shared_ptr< RawBuffergetRaw () const
 
virtual ~ADatatype ()=default
 

Private Member Functions

std::shared_ptr< RawBufferserialize () const override
 

Private Attributes

RawStereoDepthConfigcfg
 

Additional Inherited Members

- Protected Attributes inherited from dai::ADatatype
std::shared_ptr< RawBufferraw
 

Detailed Description

StereoDepthConfig message.

Definition at line 14 of file StereoDepthConfig.hpp.

Member Typedef Documentation

◆ AlgorithmControl

Definition at line 20 of file StereoDepthConfig.hpp.

◆ CensusTransform

Definition at line 22 of file StereoDepthConfig.hpp.

◆ CostAggregation

Definition at line 24 of file StereoDepthConfig.hpp.

◆ CostMatching

Definition at line 23 of file StereoDepthConfig.hpp.

◆ MedianFilter

Definition at line 19 of file StereoDepthConfig.hpp.

◆ PostProcessing

Definition at line 21 of file StereoDepthConfig.hpp.

Constructor & Destructor Documentation

◆ StereoDepthConfig() [1/2]

dai::StereoDepthConfig::StereoDepthConfig ( )

Construct StereoDepthConfig message.

Definition at line 9 of file StereoDepthConfig.cpp.

◆ StereoDepthConfig() [2/2]

dai::StereoDepthConfig::StereoDepthConfig ( std::shared_ptr< RawStereoDepthConfig ptr)
explicit

Definition at line 10 of file StereoDepthConfig.cpp.

◆ ~StereoDepthConfig()

virtual dai::StereoDepthConfig::~StereoDepthConfig ( )
virtualdefault

Member Function Documentation

◆ get()

dai::RawStereoDepthConfig dai::StereoDepthConfig::get ( ) const

Retrieve configuration data for StereoDepth.

Returns
config for stereo depth algorithm

Definition at line 147 of file StereoDepthConfig.cpp.

◆ getBilateralFilterSigma()

uint16_t dai::StereoDepthConfig::getBilateralFilterSigma ( ) const

Get sigma value for 5x5 bilateral filter

Definition at line 41 of file StereoDepthConfig.cpp.

◆ getConfidenceThreshold()

int dai::StereoDepthConfig::getConfidenceThreshold ( ) const

Get confidence threshold for disparity calculation

Definition at line 23 of file StereoDepthConfig.cpp.

◆ getDepthUnit()

dai::StereoDepthConfig::AlgorithmControl::DepthUnit dai::StereoDepthConfig::getDepthUnit ( )

Get depth unit of depth map.

Definition at line 89 of file StereoDepthConfig.cpp.

◆ getLeftRightCheckThreshold()

int dai::StereoDepthConfig::getLeftRightCheckThreshold ( ) const

Get threshold for left-right check combine

Definition at line 50 of file StereoDepthConfig.cpp.

◆ getMaxDisparity()

float dai::StereoDepthConfig::getMaxDisparity ( ) const

Useful for normalization of the disparity map.

Returns
Maximum disparity value that the node can return

Definition at line 93 of file StereoDepthConfig.cpp.

◆ getMedianFilter()

MedianFilter dai::StereoDepthConfig::getMedianFilter ( ) const

Get median filter setting

Definition at line 32 of file StereoDepthConfig.cpp.

◆ serialize()

std::shared_ptr< RawBuffer > dai::StereoDepthConfig::serialize ( ) const
overrideprivatevirtual

Reimplemented from dai::Buffer.

Definition at line 5 of file StereoDepthConfig.cpp.

◆ set()

StereoDepthConfig & dai::StereoDepthConfig::set ( dai::RawStereoDepthConfig  config)

Set explicit configuration.

Parameters
configExplicit configuration

Definition at line 151 of file StereoDepthConfig.cpp.

◆ setBilateralFilterSigma()

StereoDepthConfig & dai::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
sigmaSet sigma value for 5x5 bilateral filter. 0..65535

Definition at line 36 of file StereoDepthConfig.cpp.

◆ setConfidenceThreshold()

StereoDepthConfig & dai::StereoDepthConfig::setConfidenceThreshold ( int  confThr)

Confidence threshold for disparity calculation

Parameters
confThrConfidence threshold value 0..255

Definition at line 18 of file StereoDepthConfig.cpp.

◆ setDepthAlign()

StereoDepthConfig & dai::StereoDepthConfig::setDepthAlign ( AlgorithmControl::DepthAlign  align)
Parameters
alignSet the disparity/depth alignment: centered (between the 'left' and 'right' inputs), or from the perspective of a rectified output stream

Definition at line 13 of file StereoDepthConfig.cpp.

◆ setDepthUnit()

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

Set depth unit of depth map.

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

Definition at line 74 of file StereoDepthConfig.cpp.

◆ setDisparityShift()

StereoDepthConfig & dai::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.

Definition at line 79 of file StereoDepthConfig.cpp.

◆ setExtendedDisparity()

StereoDepthConfig & dai::StereoDepthConfig::setExtendedDisparity ( bool  enable)

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

Definition at line 59 of file StereoDepthConfig.cpp.

◆ setLeftRightCheck()

StereoDepthConfig & dai::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

Definition at line 54 of file StereoDepthConfig.cpp.

◆ setLeftRightCheckThreshold()

StereoDepthConfig & dai::StereoDepthConfig::setLeftRightCheckThreshold ( int  threshold)
Parameters
thresholdSet threshold for left-right, right-left disparity map combine, 0..255

Definition at line 45 of file StereoDepthConfig.cpp.

◆ setMedianFilter()

StereoDepthConfig & dai::StereoDepthConfig::setMedianFilter ( MedianFilter  median)
Parameters
medianSet kernel size for disparity/depth median filtering, or disable

Definition at line 27 of file StereoDepthConfig.cpp.

◆ setNumInvalidateEdgePixels()

StereoDepthConfig & dai::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.

Definition at line 84 of file StereoDepthConfig.cpp.

◆ setSubpixel()

StereoDepthConfig & dai::StereoDepthConfig::setSubpixel ( bool  enable)

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

Suitable for long range. Currently incompatible with extended disparity

Definition at line 64 of file StereoDepthConfig.cpp.

◆ setSubpixelFractionalBits()

StereoDepthConfig & dai::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.

Definition at line 69 of file StereoDepthConfig.cpp.

Member Data Documentation

◆ cfg

RawStereoDepthConfig& dai::StereoDepthConfig::cfg
private

Definition at line 16 of file StereoDepthConfig.hpp.


The documentation for this class was generated from the following files:


depthai
Author(s): Martin Peterlin
autogenerated on Sat Mar 22 2025 02:58:20