StereoDepth¶
StereoDepth node calculates the disparity/depth from the stereo camera pair (2x MonoCamera/ColorCamera).
How to place it¶
pipeline = dai.Pipeline()
stereo = pipeline.create(dai.node.StereoDepth)
dai::Pipeline pipeline;
auto stereo = pipeline.create<dai::node::StereoDepth>();
Inputs and Outputs¶
┌───────────────────┐
│ │ confidenceMap
│ ├─────────────►
│ │rectifiedLeft
│ ├─────────────►
left │ │ syncedLeft
──────────────►│-------------------├─────────────►
│ │ depth [mm]
│ ├─────────────►
│ StereoDepth │ disparity
│ ├─────────────►
right │ │ syncedRight
──────────────►│-------------------├─────────────►
│ │rectifiedRight
│ ├─────────────►
inputConfig │ | outConfig
──────────────►│-------------------├─────────────►
└───────────────────┘
left
- ImgFrame from the left stereo cameraright
- ImgFrame from the right stereo camerainputConfig
- StereoDepthConfig
Internal block diagram of StereoDepth node¶

On the diagram, red rectangle are firmware settings that are configurable via the API. Gray rectangles are settings that that are not yet exposed to the API. We plan on exposing as much configurability as possible, but please inform us if you would like to see these settings configurable sooner.
If you click on the image, you will be redirected to the webapp. Some blocks have notes that provide additional technical information.
Currently configurable blocks¶
Left-Right Check or LR-Check is used to remove incorrectly calculated disparity pixels due to occlusions at object borders (Left and Right camera views are slightly different).
Computes disparity by matching in R->L direction
Computes disparity by matching in L->R direction
Combines results from 1 and 2, running on Shave: each pixel d = disparity_LR(x,y) is compared with disparity_RL(x-d,y). If the difference is above a threshold, the pixel at (x,y) in the final disparity map is invalidated.
You can use debugDispLrCheckIt1
and debugDispLrCheckIt2
debug outputs for debugging/fine-tuning purposes.
Extended disparity mode allows detecting closer distance objects for the given baseline. This increases the maximum disparity search from 96 to 191, meaning the range is now: [0..190].
So this cuts the minimum perceivable distance in half, given that the minimum distance is now focal_length * base_line_dist / 190
instead
of focal_length * base_line_dist / 95
.
Computes disparity on the original size images (e.g. 1280x720)
Computes disparity on 2x downscaled images (e.g. 640x360)
Combines the two level disparities on Shave, effectively covering a total disparity range of 191 pixels (in relation to the original resolution).
You can use debugExtDispLrCheckIt1
and debugExtDispLrCheckIt2
debug outputs for debugging/fine-tuning purposes.
Subpixel mode improves the precision and is especially useful for long range measurements. It also helps for better estimating surface normals.
Besides the integer disparity output, the Stereo engine is programmed to dump to memory the cost volume, that is 96 levels (disparities) per pixel,
then software interpolation is done on Shave, resulting a final disparity with 3 fractional bits, resulting in significantly more granular depth
steps (8 additional steps between the integer-pixel depth steps), and also theoretically, longer-distance depth viewing - as the maximum depth
is no longer limited by a feature being a full integer pixel-step apart, but rather 1/8 of a pixel. In this mode, stereo cameras perform: 94 depth steps * 8 subpixel depth steps + 2 (min/max values) = 754 depth steps
For comparison of normal disparity vs. subpixel disparity images, click here.
Depth Filtering / Depth Post-Processing is performed at the end of the depth pipeline. It helps with noise reduction and overall depth quality.
This is a non-edge preserving Median filter, which can be used to reduce noise and smoothen the depth map. Median filter is implemented in hardware, so it’s the fastest filter.
-
enum
dai
::
MedianFilter
Median filter config for disparity post-processing
Values:
-
enumerator
MEDIAN_OFF
-
enumerator
KERNEL_3x3
-
enumerator
KERNEL_5x5
-
enumerator
KERNEL_7x7
-
enumerator
Speckle Filter is used to reduce the speckle noise. Speckle noise is a region with huge variance between neighboring disparity/depth pixels, and speckle filter tries to filter this region.
-
struct
dai::RawStereoDepthConfig::PostProcessing
::
SpeckleFilter
Speckle filtering. Removes speckle noise.
Public Members
-
bool
enable
= false Whether to enable or disable the filter.
-
std::uint32_t
speckleRange
= 50 Speckle search range.
-
bool
Temporal Filter is intended to improve the depth data persistency by manipulating per-pixel values based on previous frames. The filter performs a single pass on the data, adjusting the depth values while also updating the tracking history. In cases where the pixel data is missing or invalid, the filter uses a user-defined persistency mode to decide whether the missing value should be rectified with stored data. Note that due to its reliance on historic data the filter may introduce visible blurring/smearing artifacts, and therefore is best-suited for static scenes.
-
struct
dai::RawStereoDepthConfig::PostProcessing
::
TemporalFilter
Temporal filtering with optional persistence.
Public Types
-
enum
PersistencyMode
Persistency algorithm type.
Values:
-
enumerator
PERSISTENCY_OFF
-
enumerator
VALID_8_OUT_OF_8
-
enumerator
VALID_2_IN_LAST_3
-
enumerator
VALID_2_IN_LAST_4
-
enumerator
VALID_2_OUT_OF_8
-
enumerator
VALID_1_IN_LAST_2
-
enumerator
VALID_1_IN_LAST_5
-
enumerator
VALID_1_IN_LAST_8
-
enumerator
PERSISTENCY_INDEFINITELY
-
enumerator
Public Members
-
bool
enable
= false Whether to enable or disable the filter.
-
PersistencyMode
persistencyMode
= PersistencyMode::VALID_2_IN_LAST_4 Persistency mode. If the current disparity/depth value is invalid, it will be replaced by an older value, based on persistency mode.
-
float
alpha
= 0.4f 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.
-
std::int32_t
delta
= 0 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.
-
enum
Spatial Edge-Preserving Filter will fill invalid depth pixels with valid neighboring depth pixels. It performs a series of 1D horizontal and vertical passes or iterations, to enhance the smoothness of the reconstructed data. It is based on this research paper.
-
struct
dai::RawStereoDepthConfig::PostProcessing
::
SpatialFilter
1D edge-preserving spatial filter using high-order domain transform.
Public Members
-
bool
enable
= false Whether to enable or disable the filter.
-
std::uint8_t
holeFillingRadius
= 2 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.
-
float
alpha
= 0.5f The Alpha factor in an exponential moving average with Alpha=1 - no filter. Alpha = 0 - infinite filter. Determines the amount of smoothing.
-
std::int32_t
delta
= 0 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.
-
std::int32_t
numIterations
= 1 Nubmer of iterations over the image in both horizontal and vertical direction.
-
bool
Threshold Filter filters out all disparity/depth pixels outside the configured min/max threshold values.
-
class
depthai.RawStereoDepthConfig.PostProcessing.
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
Decimation Filter will sub-samples the depth map, which means it reduces the depth scene complexity and allows
other filters to run faster. Setting decimationFactor
to 2 will downscale 1280x800 depth map to 640x400.
-
struct
dai::RawStereoDepthConfig::PostProcessing
::
DecimationFilter
Decimation filter. Reduces the depth scene complexity. The filter runs on kernel sizes [2x2] to [8x8] pixels.
Public Types
-
enum
DecimationMode
Decimation algorithm type.
Values:
-
enumerator
PIXEL_SKIPPING
-
enumerator
NON_ZERO_MEDIAN
-
enumerator
NON_ZERO_MEAN
-
enumerator
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.
-
enum
Mesh files (homography matrix) are generated using the camera intrinsics, distortion coeffs, and rectification rotations. These files helps in overcoming the distortions in the camera increasing the accuracy and also help in when wide FOV lens are used.
Note
Currently mesh files are generated only for stereo cameras on the host during calibration. The generated mesh files are stored in depthai/resources which users can load to the device. This process will be moved to on device in the upcoming releases.
-
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
-
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
-
void
dai::node::StereoDepth
::
setMeshStep
(int width, int height) Set the distance between mesh points. Default: (16, 16)
Confidence threshold: Stereo depth algorithm searches for the matching feature from right camera point to the left image (along the 96 disparity levels). During this process it computes the cost for each disparity level and chooses the minimal cost between two disparities and uses it to compute the confidence at each pixel. Stereo node will output disparity/depth pixels only where depth confidence is below the confidence threshold (lower the confidence value means better depth accuracy).
LR check threshold: Disparity is considered for the output when the difference between LR and RL disparities is smaller than the LR check threshold.
-
StereoDepthConfig &
dai::StereoDepthConfig
::
setConfidenceThreshold
(int confThr) Confidence threshold for disparity calculation
- Parameters
confThr
: Confidence threshold value 0..255
-
StereoDepthConfig &
dai::StereoDepthConfig
::
setLeftRightCheckThreshold
(int threshold) - Parameters
threshold
: Set threshold for left-right, right-left disparity map combine, 0..255
Limitations¶
Median filtering is disabled when subpixel mode is set to 4 or 5 bits.
For RGB-depth alignment the RGB camera has to be placed on the same horizontal line as the stereo camera pair.
Stereo depth FPS¶
Stereo depth mode |
FPS for 1280x720 |
FPS for 640x400 |
---|---|---|
Standard mode |
60 |
110 |
Left-Right Check |
55 |
105 |
Subpixel Disparity |
45 |
105 |
Extended Disparity |
54 |
105 |
Subpixel + LR check |
34 |
96 |
Extended + LR check |
26 |
62 |
All stereo modes were measured for depth
output with 5x5 median filter enabled. For 720P, mono cameras were set
to 60 FPS and for 400P mono cameras were set to 110 FPS.
Usage¶
pipeline = dai.Pipeline()
stereo = pipeline.create(dai.node.StereoDepth)
# Better handling for occlusions:
stereo.setLeftRightCheck(False)
# Closer-in minimum depth, disparity range is doubled:
stereo.setExtendedDisparity(False)
# Better accuracy for longer distance, fractional disparity 32-levels:
stereo.setSubpixel(False)
# Define and configure MonoCamera nodes beforehand
left.out.link(stereo.left)
right.out.link(stereo.right)
dai::Pipeline pipeline;
auto stereo = pipeline.create<dai::node::StereoDepth>();
// Better handling for occlusions:
stereo->setLeftRightCheck(false);
// Closer-in minimum depth, disparity range is doubled:
stereo->setExtendedDisparity(false);
// Better accuracy for longer distance, fractional disparity 32-levels:
stereo->setSubpixel(false);
// Define and configure MonoCamera nodes beforehand
left->out.link(stereo->left);
right->out.link(stereo->right);
Examples of functionality¶
RGB Depth alignment - align depth to color camera
Reference¶
-
class
depthai.node.
StereoDepth
StereoDepth node. Compute stereo disparity and depth from left-right image pair.
-
class
Connection
Connection between an Input and Output
-
class
Id
Node identificator. Unique for every node on a single Pipeline
-
class
PresetMode
Preset modes for stereo depth.
Members:
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.
-
property
name
-
property
-
Properties
alias of
depthai.StereoDepthProperties
-
property
confidenceMap
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.
-
property
debugDispCostDump
Outputs ImgFrame message that carries cost dump of disparity map. Useful for debugging/fine tuning.
-
property
debugDispLrCheckIt1
Outputs ImgFrame message that carries left-right check first iteration (before combining with second iteration) disparity map. Useful for debugging/fine tuning.
-
property
debugDispLrCheckIt2
Outputs ImgFrame message that carries left-right check second iteration (before combining with first iteration) disparity map. Useful for debugging/fine tuning.
-
property
debugExtDispLrCheckIt1
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.
-
property
debugExtDispLrCheckIt2
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.
-
property
depth
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
-
property
disparity
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
- Type
Outputs ImgFrame message that carries RAW8 / RAW16 encoded disparity data
-
enableDistortionCorrection
(self: depthai.node.StereoDepth, arg0: bool) → None Equivalent to useHomographyRectification(!enableDistortionCorrection)
-
getAssetManager
(*args, **kwargs) Overloaded function.
getAssetManager(self: depthai.Node) -> depthai.AssetManager
Get node AssetManager as a const reference
getAssetManager(self: depthai.Node) -> depthai.AssetManager
Get node AssetManager as a const reference
-
getInputRefs
(*args, **kwargs) Overloaded function.
getInputRefs(self: depthai.Node) -> List[depthai.Node.Input]
Retrieves reference to node inputs
getInputRefs(self: depthai.Node) -> List[depthai.Node.Input]
Retrieves reference to node inputs
-
getInputs
(self: depthai.Node) → List[depthai.Node.Input] Retrieves all nodes inputs
-
getMaxDisparity
(self: depthai.node.StereoDepth) → float Useful for normalization of the disparity map.
- Returns
Maximum disparity value that the node can return
-
getName
(self: depthai.Node) → str Retrieves nodes name
-
getOutputRefs
(*args, **kwargs) Overloaded function.
getOutputRefs(self: depthai.Node) -> List[depthai.Node.Output]
Retrieves reference to node outputs
getOutputRefs(self: depthai.Node) -> List[depthai.Node.Output]
Retrieves reference to node outputs
-
getOutputs
(self: depthai.Node) → List[depthai.Node.Output] Retrieves all nodes outputs
-
getParentPipeline
(*args, **kwargs) Overloaded function.
getParentPipeline(self: depthai.Node) -> depthai.Pipeline
getParentPipeline(self: depthai.Node) -> depthai.Pipeline
-
property
id
Id of node
-
property
initialConfig
Initial config to use for StereoDepth.
-
property
inputConfig
Input StereoDepthConfig message with ability to modify parameters in runtime. Default queue is non-blocking with size 4.
-
property
left
Input for left ImgFrame of left-right pair
Default queue is non-blocking with size 8
-
loadMeshData
(self: depthai.node.StereoDepth, dataLeft: List[int], dataRight: List[int]) → None Specify mesh calibration data for ‘left’ and ‘right’ inputs, as vectors of bytes. Overrides useHomographyRectification behavior. See loadMeshFiles for the expected data format
-
loadMeshFiles
(self: depthai.node.StereoDepth, pathLeft: Path, pathRight: Path) → None 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
-
property
outConfig
Outputs StereoDepthConfig message that contains current stereo configuration.
-
property
rectifiedLeft
Outputs ImgFrame message that carries RAW8 encoded (grayscale) rectified frame data.
-
property
rectifiedRight
Outputs ImgFrame message that carries RAW8 encoded (grayscale) rectified frame data.
-
property
right
Input for right ImgFrame of left-right pair
Default queue is non-blocking with size 8
-
setBaseline
(self: depthai.node.StereoDepth, arg0: float) → None Override baseline from calibration. Used only in disparity to depth conversion. Units are centimeters.
-
setConfidenceThreshold
(self: depthai.node.StereoDepth, arg0: int) → None Confidence threshold for disparity calculation
- Parameter
confThr
: Confidence threshold value 0..255
- Parameter
-
setDefaultProfilePreset
(self: depthai.node.StereoDepth, arg0: depthai.node.StereoDepth.PresetMode) → None Sets a default preset based on specified option.
- Parameter
mode
: Stereo depth preset mode
- Parameter
-
setDepthAlign
(*args, **kwargs) Overloaded function.
setDepthAlign(self: depthai.node.StereoDepth, align: depthai.RawStereoDepthConfig.AlgorithmControl.DepthAlign) -> None
- Parameter
align
: Set the disparity/depth alignment: centered (between the ‘left’ and ‘right’ inputs), or from the perspective of a rectified output stream
setDepthAlign(self: depthai.node.StereoDepth, camera: depthai.CameraBoardSocket) -> None
- Parameter
camera
: Set the camera from whose perspective the disparity/depth will be aligned
-
setEmptyCalibration
(self: depthai.node.StereoDepth) → None Specify that a passthrough/dummy calibration should be used, when input frames are already rectified (e.g. sourced from recordings on the host)
-
setExtendedDisparity
(self: depthai.node.StereoDepth, enable: bool) → None 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
-
setFocalLength
(self: depthai.node.StereoDepth, arg0: float) → None Override focal length from calibration. Used only in disparity to depth conversion. Units are pixels.
-
setFocalLengthFromCalibration
(self: depthai.node.StereoDepth, arg0: bool) → None Whether to use focal length from calibration intrinsics or calculate based on calibration FOV. Default value is true.
-
setInputResolution
(*args, **kwargs) Overloaded function.
setInputResolution(self: depthai.node.StereoDepth, width: int, height: int) -> None
Specify input resolution size
Optional if MonoCamera exists, otherwise necessary
setInputResolution(self: depthai.node.StereoDepth, resolution: Tuple[int, int]) -> None
Specify input resolution size
Optional if MonoCamera exists, otherwise necessary
-
setLeftRightCheck
(self: depthai.node.StereoDepth, enable: bool) → None Computes and combines disparities in both L-R and R-L directions, and combine them.
For better occlusion handling, discarding invalid disparity values
-
setMedianFilter
(self: depthai.node.StereoDepth, arg0: depthai.MedianFilter) → None - Parameter
median
: Set kernel size for disparity/depth median filtering, or disable
- Parameter
-
setMeshStep
(self: depthai.node.StereoDepth, width: int, height: int) → None Set the distance between mesh points. Default: (16, 16)
-
setNumFramesPool
(self: depthai.node.StereoDepth, arg0: int) → None Specify number of frames in pool.
- Parameter
numFramesPool
: How many frames should the pool have
- Parameter
-
setOutputDepth
(self: depthai.node.StereoDepth, arg0: bool) → None
-
setOutputKeepAspectRatio
(self: depthai.node.StereoDepth, keep: bool) → None Specifies whether the frames resized by setOutputSize should preserve aspect ratio, with potential cropping when enabled. Default true
-
setOutputRectified
(self: depthai.node.StereoDepth, arg0: bool) → None
-
setOutputSize
(self: depthai.node.StereoDepth, width: int, height: int) → None Specify disparity/depth output resolution size, implemented by scaling.
Currently only applicable when aligning to RGB camera
-
setPostProcessingHardwareResources
(self: depthai.node.StereoDepth, arg0: int, arg1: int) → None Specify allocated hardware resources for stereo depth. Suitable only to increase post processing runtime.
- Parameter
numShaves
: Number of shaves.
- Parameter
numMemorySlices
: Number of memory slices.
- Parameter
-
setRectification
(self: depthai.node.StereoDepth, enable: bool) → None Rectify input images or not.
-
setRectifyEdgeFillColor
(self: depthai.node.StereoDepth, color: int) → None Fill color for missing data at frame edges
- Parameter
color
: Grayscale 0..255, or -1 to replicate pixels
- Parameter
-
setRectifyMirrorFrame
(self: depthai.node.StereoDepth, arg0: bool) → None 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.
- Parameter
enable
: True for normal disparity/depth, otherwise mirrored
- Parameter
-
setRuntimeModeSwitch
(self: depthai.node.StereoDepth, arg0: bool) → None 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.
-
setSubpixel
(self: depthai.node.StereoDepth, enable: bool) → None Computes disparity with sub-pixel interpolation (3 fractional bits by default).
Suitable for long range. Currently incompatible with extended disparity
-
setSubpixelFractionalBits
(self: depthai.node.StereoDepth, subpixelFractionalBits: int) → None 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.
-
property
syncedLeft
Passthrough ImgFrame message from ‘left’ Input.
-
property
syncedRight
Passthrough ImgFrame message from ‘right’ Input.
-
useHomographyRectification
(self: depthai.node.StereoDepth, arg0: bool) → None 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.
- Parameter
useHomographyRectification
: true: 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.
- Parameter
-
class
-
class
dai::node
::
StereoDepth
: public dai::NodeCRTP<Node, StereoDepth, StereoDepthProperties>¶ StereoDepth node. Compute stereo disparity and depth from left-right image pair.
Public Types
Public Functions
-
void
setEmptyCalibration
()¶ Specify that a passthrough/dummy calibration should be used, when input frames are already rectified (e.g. sourced from recordings on the host)
-
void
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
-
void
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
-
void
setMeshStep
(int width, int height) Set the distance between mesh points. Default: (16, 16)
-
void
setInputResolution
(int width, int height)¶ Specify input resolution size
Optional if MonoCamera exists, otherwise necessary
-
void
setInputResolution
(std::tuple<int, int> resolution)¶ Specify input resolution size
Optional if MonoCamera exists, otherwise necessary
-
void
setOutputSize
(int width, int height)¶ Specify disparity/depth output resolution size, implemented by scaling.
Currently only applicable when aligning to RGB camera
-
void
setOutputKeepAspectRatio
(bool keep)¶ Specifies whether the frames resized by
setOutputSize
should preserve aspect ratio, with potential cropping when enabled. Defaulttrue
-
void
setMedianFilter
(dai::MedianFilter median)¶ - Parameters
median
: Set kernel size for disparity/depth median filtering, or disable
-
void
setDepthAlign
(Properties::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
-
void
setDepthAlign
(CameraBoardSocket camera)¶ - Parameters
camera
: Set the camera from whose perspective the disparity/depth will be aligned
-
void
setConfidenceThreshold
(int confThr)¶ Confidence threshold for disparity calculation
- Parameters
confThr
: Confidence threshold value 0..255
-
void
setRectification
(bool enable)¶ Rectify input images or not.
-
void
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
-
void
setSubpixel
(bool enable)¶ Computes disparity with sub-pixel interpolation (3 fractional bits by default).
Suitable for long range. Currently incompatible with extended disparity
-
void
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.
-
void
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
-
void
setRectifyEdgeFillColor
(int color)¶ Fill color for missing data at frame edges
- Parameters
color
: Grayscale 0..255, or -1 to replicate pixels
-
void
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
enable
: True for normal disparity/depth, otherwise mirrored
-
void
setOutputRectified
(bool enable)¶ Enable outputting rectified frames. Optimizes computation on device side when disabled. DEPRECATED. The outputs are auto-enabled if used
-
void
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
-
void
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.
-
void
setNumFramesPool
(int numFramesPool)¶ Specify number of frames in pool.
- Parameters
numFramesPool
: How many frames should the pool have
-
float
getMaxDisparity
() const¶ Useful for normalization of the disparity map.
- Return
Maximum disparity value that the node can return
-
void
setPostProcessingHardwareResources
(int numShaves, int numMemorySlices)¶ Specify allocated hardware resources for stereo depth. Suitable only to increase post processing runtime.
- Parameters
numShaves
: Number of shaves.numMemorySlices
: Number of memory slices.
-
void
setDefaultProfilePreset
(PresetMode mode)¶ Sets a default preset based on specified option.
- Parameters
mode
: Stereo depth preset mode
-
void
setFocalLengthFromCalibration
(bool focalLengthFromCalibration)¶ Whether to use focal length from calibration intrinsics or calculate based on calibration FOV. Default value is true.
-
void
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
useHomographyRectification
: true: 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.
-
void
enableDistortionCorrection
(bool enableDistortionCorrection)¶ Equivalent to useHomographyRectification(!enableDistortionCorrection)
-
void
setBaseline
(float baseline)¶ Override baseline from calibration. Used only in disparity to depth conversion. Units are centimeters.
-
void
setFocalLength
(float focalLength)¶ Override focal length from calibration. Used only in disparity to depth conversion. Units are pixels.
Public Members
-
StereoDepthConfig
initialConfig
¶ Initial config to use for StereoDepth.
-
Input
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.
-
Input
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
-
Input
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
-
Output
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
-
Output
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
-
Output
syncedLeft
= {*this, "syncedLeft", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}¶ Passthrough ImgFrame message from ‘left’ Input.
-
Output
syncedRight
= {*this, "syncedRight", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}¶ Passthrough ImgFrame message from ‘right’ Input.
-
Output
rectifiedLeft
= {*this, "rectifiedLeft", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}¶ Outputs ImgFrame message that carries RAW8 encoded (grayscale) rectified frame data.
-
Output
rectifiedRight
= {*this, "rectifiedRight", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}¶ Outputs ImgFrame message that carries RAW8 encoded (grayscale) rectified frame data.
-
Output
outConfig
= {*this, "outConfig", Output::Type::MSender, {{DatatypeEnum::StereoDepthConfig, false}}}¶ Outputs StereoDepthConfig message that contains current stereo configuration.
-
Output
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.
-
Output
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.
-
Output
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.
-
Output
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.
-
Output
debugDispCostDump
= {*this, "debugDispCostDump", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}¶ Outputs ImgFrame message that carries cost dump of disparity map. Useful for debugging/fine tuning.
-
Output
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.
Public Static Attributes
-
static constexpr const char *
NAME
= "StereoDepth"¶
Private Members
-
PresetMode
presetMode
= PresetMode::HIGH_DENSITY¶
-
std::shared_ptr<RawStereoDepthConfig>
rawConfig
¶
-
void
Disparity¶
Disparity refers to the distance between two corresponding points in the left and right image of a stereo pair.

When calculating the disparity, each pixel in the disparity map gets assigned a confidence value 0..255
by the stereo matching algorithm,
as:
0
- maximum confidence that it holds a valid value255
- minimum confidence, so there is more chance that the value is incorrect
(this confidence score is kind-of inverted, if say comparing with NN)
For the final disparity map, a filtering is applied based on the confidence threshold value: the pixels that have their confidence score larger than
the threshold get invalidated, i.e. their disparity value is set to zero. You can set the confidence threshold with stereo.initialConfig.setConfidenceThreshold()
.
Measuring real-world object dimensions¶
Because the depth map contains the Z distance, objects in parallel with the camera are measured accurately standard. For objects not in parallel, the Euclidean distance calculation can be used. Please refer to the below:

When running eg. the RGB & MobilenetSSD with spatial data example, you could calculate the distance to the detected object from XYZ coordinates (SpatialImgDetections) using the code below (after code line 143
of the example):
distance = math.sqrt(detection.spatialCoordinates.x ** 2 + detection.spatialCoordinates.y ** 2 + detection.spatialCoordinates.z ** 2) # mm
Got questions?
We’re always happy to help with code or other questions you might have.