Public Types | Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | Private Attributes | List of all members
dai::node::StereoDepth Class Reference

StereoDepth node. Compute stereo disparity and depth from left-right image pair. More...

#include <StereoDepth.hpp>

Inheritance diagram for dai::node::StereoDepth:
Inheritance graph
[legend]

Public Types

enum  PresetMode : std::uint32_t {
  PresetMode::HIGH_ACCURACY, PresetMode::HIGH_DENSITY, PresetMode::DEFAULT, PresetMode::FACE,
  PresetMode::HIGH_DETAIL, PresetMode::ROBOTICS
}
 
- Public Types inherited from dai::NodeCRTP< Node, StereoDepth, StereoDepthProperties >
using Properties = StereoDepthProperties
 
- Public Types inherited from dai::Node
using Id = std::int64_t
 Node identificator. Unique for every node on a single Pipeline. More...
 

Public Member Functions

void enableDistortionCorrection (bool enableDistortionCorrection)
 
float getMaxDisparity () const
 
void loadMeshData (const std::vector< std::uint8_t > &dataLeft, const std::vector< std::uint8_t > &dataRight)
 
void loadMeshFiles (const dai::Path &pathLeft, const dai::Path &pathRight)
 
void setAlphaScaling (float alpha)
 
void setBaseline (float baseline)
 
void setConfidenceThreshold (int confThr)
 
void setDefaultProfilePreset (PresetMode mode)
 
void setDepthAlign (CameraBoardSocket camera)
 
void setDepthAlign (Properties::DepthAlign align)
 
void setDepthAlignmentUseSpecTranslation (bool specTranslation)
 
void setDisparityToDepthUseSpecTranslation (bool specTranslation)
 
void setEmptyCalibration ()
 
void setExtendedDisparity (bool enable)
 
void setFocalLength (float focalLength)
 
void setFocalLengthFromCalibration (bool focalLengthFromCalibration)
 
void setInputResolution (int width, int height)
 
void setInputResolution (std::tuple< int, int > resolution)
 
void setLeftRightCheck (bool enable)
 
void setMedianFilter (dai::MedianFilter median)
 
void setMeshStep (int width, int height)
 
void setNumFramesPool (int numFramesPool)
 
void setOutputDepth (bool enable)
 
void setOutputKeepAspectRatio (bool keep)
 
void setOutputRectified (bool enable)
 
void setOutputSize (int width, int height)
 
void setPostProcessingHardwareResources (int numShaves, int numMemorySlices)
 
void setRectification (bool enable)
 
void setRectificationUseSpecTranslation (bool specTranslation)
 
void setRectifyEdgeFillColor (int color)
 
void setRectifyMirrorFrame (bool enable)
 
void setRuntimeModeSwitch (bool enable)
 
void setSubpixel (bool enable)
 
void setSubpixelFractionalBits (int subpixelFractionalBits)
 
 StereoDepth (const std::shared_ptr< PipelineImpl > &par, int64_t nodeId)
 
 StereoDepth (const std::shared_ptr< PipelineImpl > &par, int64_t nodeId, std::unique_ptr< Properties > props)
 
void useHomographyRectification (bool useHomographyRectification)
 
- Public Member Functions inherited from dai::NodeCRTP< Node, StereoDepth, StereoDepthProperties >
std::unique_ptr< Nodeclone () const override
 
const char * getName () const override
 
- Public Member Functions inherited from dai::Node
virtual std::unique_ptr< Nodeclone () const =0
 Deep copy the node. More...
 
AssetManagergetAssetManager ()
 Get node AssetManager as a reference. More...
 
const AssetManagergetAssetManager () const
 Get node AssetManager as a const reference. More...
 
std::vector< Input * > getInputRefs ()
 Retrieves reference to node inputs. More...
 
std::vector< const Input * > getInputRefs () const
 Retrieves reference to node inputs. More...
 
std::vector< InputgetInputs ()
 Retrieves all nodes inputs. More...
 
virtual const char * getName () const =0
 Retrieves nodes name. More...
 
std::vector< Output * > getOutputRefs ()
 Retrieves reference to node outputs. More...
 
std::vector< const Output * > getOutputRefs () const
 Retrieves reference to node outputs. More...
 
std::vector< OutputgetOutputs ()
 Retrieves all nodes outputs. More...
 
Pipeline getParentPipeline ()
 
const Pipeline getParentPipeline () const
 
 Node (const std::shared_ptr< PipelineImpl > &p, Id nodeId, std::unique_ptr< Properties > props)
 Constructs Node. More...
 
virtual ~Node ()=default
 

Public Attributes

Output confidenceMap {*this, "confidenceMap", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}
 
Output debugDispCostDump {*this, "debugDispCostDump", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}
 
Output debugDispLrCheckIt1 {*this, "debugDispLrCheckIt1", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}
 
Output debugDispLrCheckIt2 {*this, "debugDispLrCheckIt2", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}
 
Output debugExtDispLrCheckIt1 {*this, "debugExtDispLrCheckIt1", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}
 
Output debugExtDispLrCheckIt2 {*this, "debugExtDispLrCheckIt2", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}
 
Output depth {*this, "depth", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}
 
Output disparity {*this, "disparity", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}
 
StereoDepthConfig initialConfig
 
Input inputConfig {*this, "inputConfig", Input::Type::SReceiver, false, 4, {{DatatypeEnum::StereoDepthConfig, false}}}
 
Input left {*this, "left", Input::Type::SReceiver, false, 8, true, {{DatatypeEnum::ImgFrame, true}}}
 
Output outConfig {*this, "outConfig", Output::Type::MSender, {{DatatypeEnum::StereoDepthConfig, false}}}
 
Output rectifiedLeft {*this, "rectifiedLeft", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}
 
Output rectifiedRight {*this, "rectifiedRight", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}
 
Input right {*this, "right", Input::Type::SReceiver, false, 8, true, {{DatatypeEnum::ImgFrame, true}}}
 
Output syncedLeft {*this, "syncedLeft", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}
 
Output syncedRight {*this, "syncedRight", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}
 
- Public Attributes inherited from dai::NodeCRTP< Node, StereoDepth, StereoDepthProperties >
Propertiesproperties
 Underlying properties. More...
 
- Public Attributes inherited from dai::Node
const Id id
 Id of node. More...
 
Propertiesproperties
 

Static Public Attributes

constexpr static const char * NAME = "StereoDepth"
 

Protected Member Functions

PropertiesgetProperties ()
 
- Protected Member Functions inherited from dai::Node
virtual tl::optional< OpenVINO::VersiongetRequiredOpenVINOVersion ()
 
void setInputMapRefs (InputMap *inMapRef)
 
void setInputMapRefs (std::initializer_list< InputMap * > l)
 
void setInputRefs (Input *inRef)
 
void setInputRefs (std::initializer_list< Input * > l)
 
void setOutputMapRefs (OutputMap *outMapRef)
 
void setOutputMapRefs (std::initializer_list< OutputMap * > l)
 
void setOutputRefs (Output *outRef)
 
void setOutputRefs (std::initializer_list< Output * > l)
 

Private Attributes

PresetMode presetMode = PresetMode::HIGH_DENSITY
 
std::shared_ptr< RawStereoDepthConfigrawConfig
 

Additional Inherited Members

- Protected Attributes inherited from dai::Node
AssetManager assetManager
 
std::unordered_map< std::string, InputMap * > inputMapRefs
 
std::unordered_map< std::string, Input * > inputRefs
 
std::unordered_map< std::string, OutputMap * > outputMapRefs
 
std::unordered_map< std::string, Output * > outputRefs
 
std::weak_ptr< PipelineImplparent
 
copyable_unique_ptr< PropertiespropertiesHolder
 

Detailed Description

StereoDepth node. Compute stereo disparity and depth from left-right image pair.

Definition at line 15 of file StereoDepth.hpp.

Member Enumeration Documentation

◆ PresetMode

enum dai::node::StereoDepth::PresetMode : std::uint32_t
strong

Preset modes for stereo depth.

Enumerator
HIGH_ACCURACY 

Prefers accuracy over density. More invalid depth values, but less outliers.

HIGH_DENSITY 

Prefers density over accuracy. Less invalid depth values, but more outliers.

DEFAULT 
FACE 
HIGH_DETAIL 
ROBOTICS 

Definition at line 22 of file StereoDepth.hpp.

Constructor & Destructor Documentation

◆ StereoDepth() [1/2]

dai::node::StereoDepth::StereoDepth ( const std::shared_ptr< PipelineImpl > &  par,
int64_t  nodeId 
)

Definition at line 13 of file StereoDepth.cpp.

◆ StereoDepth() [2/2]

dai::node::StereoDepth::StereoDepth ( const std::shared_ptr< PipelineImpl > &  par,
int64_t  nodeId,
std::unique_ptr< Properties props 
)

Definition at line 14 of file StereoDepth.cpp.

Member Function Documentation

◆ enableDistortionCorrection()

void dai::node::StereoDepth::enableDistortionCorrection ( bool  enableDistortionCorrection)

Equivalent to useHomographyRectification(!enableDistortionCorrection)

Definition at line 178 of file StereoDepth.cpp.

◆ getMaxDisparity()

float dai::node::StereoDepth::getMaxDisparity ( ) const

Useful for normalization of the disparity map.

Returns
Maximum disparity value that the node can return

Definition at line 161 of file StereoDepth.cpp.

◆ getProperties()

StereoDepth::Properties & dai::node::StereoDepth::getProperties ( )
protectedvirtual

Reimplemented from dai::Node.

Definition at line 37 of file StereoDepth.cpp.

◆ loadMeshData()

void dai::node::StereoDepth::loadMeshData ( const std::vector< std::uint8_t > &  dataLeft,
const std::vector< std::uint8_t > &  dataRight 
)

Specify mesh calibration data for 'left' and 'right' inputs, as vectors of bytes. Overrides useHomographyRectification behavior. See loadMeshFiles for the expected data format

Definition at line 47 of file StereoDepth.cpp.

◆ loadMeshFiles()

void dai::node::StereoDepth::loadMeshFiles ( const dai::Path pathLeft,
const dai::Path pathRight 
)

Specify local filesystem paths to the mesh calibration files for 'left' and 'right' inputs.

When a mesh calibration is set, it overrides the camera intrinsics/extrinsics matrices. Overrides useHomographyRectification behavior. Mesh format: a sequence of (y,x) points as 'float' with coordinates from the input image to be mapped in the output. The mesh can be subsampled, configured by setMeshStep.

With a 1280x800 resolution and the default (16,16) step, the required mesh size is:

width: 1280 / 16 + 1 = 81

height: 800 / 16 + 1 = 51

Definition at line 67 of file StereoDepth.cpp.

◆ setAlphaScaling()

void dai::node::StereoDepth::setAlphaScaling ( float  alpha)

Free scaling parameter between 0 (when all the pixels in the undistorted image are valid) and 1 (when all the source image pixels are retained in the undistorted image). On some high distortion lenses, and/or due to rectification (image rotated) invalid areas may appear even with alpha=0, in these cases alpha < 0.0 helps removing invalid areas. See getOptimalNewCameraMatrix from opencv for more details.

Definition at line 202 of file StereoDepth.cpp.

◆ setBaseline()

void dai::node::StereoDepth::setBaseline ( float  baseline)

Override baseline from calibration. Used only in disparity to depth conversion. Units are centimeters.

Definition at line 182 of file StereoDepth.cpp.

◆ setConfidenceThreshold()

void dai::node::StereoDepth::setConfidenceThreshold ( int  confThr)

Confidence threshold for disparity calculation

Parameters
confThrConfidence threshold value 0..255

Definition at line 114 of file StereoDepth.cpp.

◆ setDefaultProfilePreset()

void dai::node::StereoDepth::setDefaultProfilePreset ( PresetMode  mode)

Sets a default preset based on specified option.

Parameters
modeStereo depth preset mode

Definition at line 206 of file StereoDepth.cpp.

◆ setDepthAlign() [1/2]

void dai::node::StereoDepth::setDepthAlign ( CameraBoardSocket  camera)
Parameters
cameraSet the camera from whose perspective the disparity/depth will be aligned

Definition at line 111 of file StereoDepth.cpp.

◆ setDepthAlign() [2/2]

void dai::node::StereoDepth::setDepthAlign ( Properties::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 106 of file StereoDepth.cpp.

◆ setDepthAlignmentUseSpecTranslation()

void dai::node::StereoDepth::setDepthAlignmentUseSpecTranslation ( bool  specTranslation)

Use baseline information for depth alignment from specs (design data) or from calibration. Default: true

Definition at line 198 of file StereoDepth.cpp.

◆ setDisparityToDepthUseSpecTranslation()

void dai::node::StereoDepth::setDisparityToDepthUseSpecTranslation ( bool  specTranslation)

Use baseline information for disparity to depth conversion from specs (design data) or from calibration. Default: true

Definition at line 190 of file StereoDepth.cpp.

◆ setEmptyCalibration()

void dai::node::StereoDepth::setEmptyCalibration ( )

Specify that a passthrough/dummy calibration should be used, when input frames are already rectified (e.g. sourced from recordings on the host)

Definition at line 42 of file StereoDepth.cpp.

◆ setExtendedDisparity()

void dai::node::StereoDepth::setExtendedDisparity ( bool  enable)

Disparity range increased from 0-95 to 0-190, combined from full resolution and downscaled images.

Suitable for short range objects. Currently incompatible with sub-pixel disparity

Definition at line 133 of file StereoDepth.cpp.

◆ setFocalLength()

void dai::node::StereoDepth::setFocalLength ( float  focalLength)

Override focal length from calibration. Used only in disparity to depth conversion. Units are pixels.

Definition at line 186 of file StereoDepth.cpp.

◆ setFocalLengthFromCalibration()

void dai::node::StereoDepth::setFocalLengthFromCalibration ( bool  focalLengthFromCalibration)

Whether to use focal length from calibration intrinsics or calculate based on calibration FOV. Default value is true.

Definition at line 170 of file StereoDepth.cpp.

◆ setInputResolution() [1/2]

void dai::node::StereoDepth::setInputResolution ( int  width,
int  height 
)

Specify input resolution size

Optional if MonoCamera exists, otherwise necessary

Definition at line 88 of file StereoDepth.cpp.

◆ setInputResolution() [2/2]

void dai::node::StereoDepth::setInputResolution ( std::tuple< int, int >  resolution)

Specify input resolution size

Optional if MonoCamera exists, otherwise necessary

Definition at line 92 of file StereoDepth.cpp.

◆ setLeftRightCheck()

void dai::node::StereoDepth::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 121 of file StereoDepth.cpp.

◆ setMedianFilter()

void dai::node::StereoDepth::setMedianFilter ( dai::MedianFilter  median)
Parameters
medianSet kernel size for disparity/depth median filtering, or disable

Definition at line 102 of file StereoDepth.cpp.

◆ setMeshStep()

void dai::node::StereoDepth::setMeshStep ( int  width,
int  height 
)

Set the distance between mesh points. Default: (16, 16)

Definition at line 83 of file StereoDepth.cpp.

◆ setNumFramesPool()

void dai::node::StereoDepth::setNumFramesPool ( int  numFramesPool)

Specify number of frames in pool.

Parameters
numFramesPoolHow many frames should the pool have

Definition at line 157 of file StereoDepth.cpp.

◆ setOutputDepth()

void dai::node::StereoDepth::setOutputDepth ( bool  enable)

Enable outputting 'depth' stream (converted from disparity). In certain configurations, this will disable 'disparity' stream. DEPRECATED. The output is auto-enabled if used

Definition at line 148 of file StereoDepth.cpp.

◆ setOutputKeepAspectRatio()

void dai::node::StereoDepth::setOutputKeepAspectRatio ( bool  keep)

Specifies whether the frames resized by setOutputSize should preserve aspect ratio, with potential cropping when enabled. Default true

Definition at line 99 of file StereoDepth.cpp.

◆ setOutputRectified()

void dai::node::StereoDepth::setOutputRectified ( bool  enable)

Enable outputting rectified frames. Optimizes computation on device side when disabled. DEPRECATED. The outputs are auto-enabled if used

Definition at line 144 of file StereoDepth.cpp.

◆ setOutputSize()

void dai::node::StereoDepth::setOutputSize ( int  width,
int  height 
)

Specify disparity/depth output resolution size, implemented by scaling.

Currently only applicable when aligning to RGB camera

Definition at line 95 of file StereoDepth.cpp.

◆ setPostProcessingHardwareResources()

void dai::node::StereoDepth::setPostProcessingHardwareResources ( int  numShaves,
int  numMemorySlices 
)

Specify allocated hardware resources for stereo depth. Suitable only to increase post processing runtime.

Parameters
numShavesNumber of shaves.
numMemorySlicesNumber of memory slices.

Definition at line 165 of file StereoDepth.cpp.

◆ setRectification()

void dai::node::StereoDepth::setRectification ( bool  enable)

Rectify input images or not.

Definition at line 118 of file StereoDepth.cpp.

◆ setRectificationUseSpecTranslation()

void dai::node::StereoDepth::setRectificationUseSpecTranslation ( bool  specTranslation)

Obtain rectification matrices using spec translation (design data) or from calibration in calculations. Should be used only for debugging. Default: false

Definition at line 194 of file StereoDepth.cpp.

◆ setRectifyEdgeFillColor()

void dai::node::StereoDepth::setRectifyEdgeFillColor ( int  color)

Fill color for missing data at frame edges

Parameters
colorGrayscale 0..255, or -1 to replicate pixels

Definition at line 137 of file StereoDepth.cpp.

◆ setRectifyMirrorFrame()

void dai::node::StereoDepth::setRectifyMirrorFrame ( bool  enable)

DEPRECATED function. It was removed, since rectified images are not flipped anymore. Mirror rectified frames, only when LR-check mode is disabled. Default true. The mirroring is required to have a normal non-mirrored disparity/depth output.

A side effect of this option is disparity alignment to the perspective of left or right input: false: mapped to left and mirrored, true: mapped to right. With LR-check enabled, this option is ignored, none of the outputs are mirrored, and disparity is mapped to right.

Parameters
enableTrue for normal disparity/depth, otherwise mirrored

Definition at line 140 of file StereoDepth.cpp.

◆ setRuntimeModeSwitch()

void dai::node::StereoDepth::setRuntimeModeSwitch ( bool  enable)

Enable runtime stereo mode switch, e.g. from standard to LR-check. Note: when enabled resources allocated for worst case to enable switching to any mode.

Definition at line 153 of file StereoDepth.cpp.

◆ setSubpixel()

void dai::node::StereoDepth::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 125 of file StereoDepth.cpp.

◆ setSubpixelFractionalBits()

void dai::node::StereoDepth::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 129 of file StereoDepth.cpp.

◆ useHomographyRectification()

void dai::node::StereoDepth::useHomographyRectification ( bool  useHomographyRectification)

Use 3x3 homography matrix for stereo rectification instead of sparse mesh generated on device. Default behaviour is AUTO, for lenses with FOV over 85 degrees sparse mesh is used, otherwise 3x3 homography. If custom mesh data is provided through loadMeshData or loadMeshFiles this option is ignored.

Parameters
useHomographyRectificationtrue: 3x3 homography matrix generated from calibration data is used for stereo rectification, can't correct lens distortion. false: sparse mesh is generated on-device from calibration data with mesh step specified with setMeshStep (Default: (16, 16)), can correct lens distortion. Implementation for generating the mesh is same as opencv's initUndistortRectifyMap function. Only the first 8 distortion coefficients are used from calibration data.

Definition at line 174 of file StereoDepth.cpp.

Member Data Documentation

◆ confidenceMap

Output dai::node::StereoDepth::confidenceMap {*this, "confidenceMap", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries RAW8 confidence map. Lower values means higher confidence of the calculated disparity value. RGB alignment, left-right check or any postproccessing (e.g. median filter) is not performed on confidence map.

Definition at line 152 of file StereoDepth.hpp.

◆ debugDispCostDump

Output dai::node::StereoDepth::debugDispCostDump {*this, "debugDispCostDump", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries cost dump of disparity map. Useful for debugging/fine tuning.

Definition at line 145 of file StereoDepth.hpp.

◆ debugDispLrCheckIt1

Output dai::node::StereoDepth::debugDispLrCheckIt1 {*this, "debugDispLrCheckIt1", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries left-right check first iteration (before combining with second iteration) disparity map. Useful for debugging/fine tuning.

Definition at line 121 of file StereoDepth.hpp.

◆ debugDispLrCheckIt2

Output dai::node::StereoDepth::debugDispLrCheckIt2 {*this, "debugDispLrCheckIt2", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries left-right check second iteration (before combining with first iteration) disparity map. Useful for debugging/fine tuning.

Definition at line 127 of file StereoDepth.hpp.

◆ debugExtDispLrCheckIt1

Output dai::node::StereoDepth::debugExtDispLrCheckIt1 {*this, "debugExtDispLrCheckIt1", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries extended left-right check first iteration (downscaled frame, before combining with second iteration) disparity map. Useful for debugging/fine tuning.

Definition at line 133 of file StereoDepth.hpp.

◆ debugExtDispLrCheckIt2

Output dai::node::StereoDepth::debugExtDispLrCheckIt2 {*this, "debugExtDispLrCheckIt2", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries extended left-right check second iteration (downscaled frame, before combining with first iteration) disparity map. Useful for debugging/fine tuning.

Definition at line 139 of file StereoDepth.hpp.

◆ depth

Output dai::node::StereoDepth::depth {*this, "depth", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries RAW16 encoded (0..65535) depth data in depth units (millimeter by default).

Non-determined / invalid depth values are set to 0

Definition at line 79 of file StereoDepth.hpp.

◆ disparity

Output dai::node::StereoDepth::disparity {*this, "disparity", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries RAW8 / RAW16 encoded disparity data: RAW8 encoded (0..95) for standard mode; RAW8 encoded (0..190) for extended disparity mode; RAW16 encoded for subpixel disparity mode:

  • 0..760 for 3 fractional bits (by default)
  • 0..1520 for 4 fractional bits
  • 0..3040 for 5 fractional bits

Definition at line 90 of file StereoDepth.hpp.

◆ initialConfig

StereoDepthConfig dai::node::StereoDepth::initialConfig

Initial config to use for StereoDepth.

Definition at line 52 of file StereoDepth.hpp.

◆ inputConfig

Input dai::node::StereoDepth::inputConfig {*this, "inputConfig", Input::Type::SReceiver, false, 4, {{DatatypeEnum::StereoDepthConfig, false}}}

Input StereoDepthConfig message with ability to modify parameters in runtime. Default queue is non-blocking with size 4.

Definition at line 58 of file StereoDepth.hpp.

◆ left

Input dai::node::StereoDepth::left {*this, "left", Input::Type::SReceiver, false, 8, true, {{DatatypeEnum::ImgFrame, true}}}

Input for left ImgFrame of left-right pair

Default queue is non-blocking with size 8

Definition at line 65 of file StereoDepth.hpp.

◆ NAME

constexpr static const char* dai::node::StereoDepth::NAME = "StereoDepth"
staticconstexpr

Definition at line 17 of file StereoDepth.hpp.

◆ outConfig

Output dai::node::StereoDepth::outConfig {*this, "outConfig", Output::Type::MSender, {{DatatypeEnum::StereoDepthConfig, false}}}

Outputs StereoDepthConfig message that contains current stereo configuration.

Definition at line 115 of file StereoDepth.hpp.

◆ presetMode

PresetMode dai::node::StereoDepth::presetMode = PresetMode::HIGH_DENSITY
private

Definition at line 42 of file StereoDepth.hpp.

◆ rawConfig

std::shared_ptr<RawStereoDepthConfig> dai::node::StereoDepth::rawConfig
private

Definition at line 43 of file StereoDepth.hpp.

◆ rectifiedLeft

Output dai::node::StereoDepth::rectifiedLeft {*this, "rectifiedLeft", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries RAW8 encoded (grayscale) rectified frame data.

Definition at line 105 of file StereoDepth.hpp.

◆ rectifiedRight

Output dai::node::StereoDepth::rectifiedRight {*this, "rectifiedRight", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries RAW8 encoded (grayscale) rectified frame data.

Definition at line 110 of file StereoDepth.hpp.

◆ right

Input dai::node::StereoDepth::right {*this, "right", Input::Type::SReceiver, false, 8, true, {{DatatypeEnum::ImgFrame, true}}}

Input for right ImgFrame of left-right pair

Default queue is non-blocking with size 8

Definition at line 72 of file StereoDepth.hpp.

◆ syncedLeft

Output dai::node::StereoDepth::syncedLeft {*this, "syncedLeft", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Passthrough ImgFrame message from 'left' Input.

Definition at line 95 of file StereoDepth.hpp.

◆ syncedRight

Output dai::node::StereoDepth::syncedRight {*this, "syncedRight", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Passthrough ImgFrame message from 'right' Input.

Definition at line 100 of file StereoDepth.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