StereoDepth

Stereo depth node calculates the dispartiy/depth from two mono cameras.

How to place it

pipeline = dai.Pipeline()
stereo = pipeline.createStereoDepth()
dai::Pipeline pipeline;
auto stereo = pipeline.create<dai::node::StereoDepth>();

Inputs and Outputs

               ┌───────────────────┐
               │                   │rectifiedLeft
               │                   ├─────────────►
left           │                   │   syncedLeft
──────────────►│                   ├─────────────►
               │                   │        depth
               │                   ├─────────────►
               │    StereoDepth    │    disparity
               │                   ├─────────────►
right          │                   │rectifiedRight
──────────────►│                   ├─────────────►
               │                   │   syncedRight
               │                   ├─────────────►
               └───────────────────┘

Message types

Disparity

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 value

  • 255 - 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.setConfidenceThreshold().

Current limitations

If one or more of the additional depth modes (lrcheck, extended, subpixel) are enabled, then:

  • median filtering is disabled on device

  • with subpixel, if both depth and disparity are used, only depth will have valid output

Otherwise, depth output is U16 (in millimeters) and median is functional.

Depth Modes

Left-Right Check

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

  1. Computes disparity by matching in R->L direction

  2. Computes disparity by matching in L->R direction

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

Extended Disparity

The extended disparity allows detecting closer distance objects for the given baseline. This increases the maximum disparity search from 96 to 191. 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.

  1. Computes disparity on the original size images (e.g. 1280x720)

  2. Computes disparity on 2x downscaled images (e.g. 640x360)

  3. Combines the two level disparities on Shave, effectively covering a total disparity range of 191 pixels (in relation to the original resolution).

Subpixel Disparity

Subpixel 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 5 fractional bits, resulting in significantly more granular depth steps (32 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/32 of a pixel.

For comparison of normal disparity vs. subpixel disparity images, click here.

Usage

pipeline = dai.Pipeline()
stereo = pipeline.createStereoDepth()

# 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);

Reference

class depthai.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

Properties

alias of depthai.StereoDepthProperties

property depth

Outputs ImgFrame message that carries RAW16 encoded (0..65535) depth data in millimeters.

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 (0..3040) for subpixel disparity mode (32 subpixel levels on top of standard mode).

Type

Outputs ImgFrame message that carries RAW8 / RAW16 encoded disparity data

getAssets(self: depthai.Node) → List[depthai.Asset]

Retrieves all nodes assets

getInputs(self: depthai.Node) → List[dai::Node::Input]

Retrieves all nodes inputs

getMaxDisparity(self: depthai.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

getOutputs(self: depthai.Node) → List[dai::Node::Output]

Retrieves all nodes outputs

property id

Id of node

property left

Input for left ImgFrame of left-right pair

Default queue is non-blocking with size 8

loadCalibrationData(self: depthai.StereoDepth, arg0: List[int])None
loadCalibrationFile(self: depthai.StereoDepth, arg0: str)None
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

setConfidenceThreshold(self: depthai.StereoDepth, confThr: int)None

Confidence threshold for disparity calculation

Parameter confThr:

Confidence threshold value 0..255

setDepthAlign(*args, **kwargs)

Overloaded function.

  1. setDepthAlign(self: depthai.StereoDepth, align: dai::StereoDepthProperties::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

  1. setDepthAlign(self: depthai.StereoDepth, camera: dai::CameraBoardSocket) -> None

Parameter camera:

Set the camera from whose perspective the disparity/depth will be aligned

setEmptyCalibration(self: depthai.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.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

setInputResolution(self: depthai.StereoDepth, width: int, height: int)None

Specify input resolution size

Optional if MonoCamera exists, otherwise necessary

setLeftRightCheck(self: depthai.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.StereoDepth, median: dai::StereoDepthProperties::MedianFilter)None
Parameter median:

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

setOutputDepth(self: depthai.StereoDepth, arg0: bool)None
setOutputRectified(self: depthai.StereoDepth, arg0: bool)None
setRectifyEdgeFillColor(self: depthai.StereoDepth, color: int)None

Fill color for missing data at frame edges

Parameter color:

Grayscale 0..255, or -1 to replicate pixels

setRectifyMirrorFrame(self: depthai.StereoDepth, enable: bool)None

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

setSubpixel(self: depthai.StereoDepth, enable: bool)None

Computes disparity with sub-pixel interpolation (5 fractional bits).

Suitable for long range. Currently incompatible with extended disparity

property syncedLeft

Passthrough ImgFrame message from ‘left’ Input.

property syncedRight

Passthrough ImgFrame message from ‘right’ Input.

class dai::node::StereoDepth : public dai::Node

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

Public Types

using Properties = dai::StereoDepthProperties

Public Functions

StereoDepth(const std::shared_ptr<PipelineImpl> &par, int64_t nodeId)
void loadCalibrationFile(const std::string &path)

Specify local filesystem path to the calibration file

Parameters
  • path: Path to calibration file. If empty use EEPROM

void loadCalibrationData(const std::vector<std::uint8_t> &data)

Specify calibration data as a vector of bytes

Parameters
  • path: Calibration data. If empty use EEPROM

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 setInputResolution(int width, int height)

Specify input resolution size

Optional if MonoCamera exists, otherwise necessary

void setMedianFilter(Properties::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 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 (5 fractional bits).

Suitable for long range. Currently incompatible with extended disparity

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)

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

float getMaxDisparity() const

Useful for normalization of the disparity map.

Return

Maximum disparity value that the node can return

Public Members

Input left = {*this, "left", Input::Type::SReceiver, false, 8, {{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, {{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 millimeters.

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 (0..3040) for subpixel disparity mode (32 subpixel levels on top of standard mode).

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.

Private Functions

std::string getName() const override

Retrieves nodes name.

std::vector<Output> getOutputs() override

Retrieves all nodes outputs.

std::vector<Input> getInputs() override

Retrieves all nodes inputs.

nlohmann::json getProperties() override
std::shared_ptr<Node> clone() override

Private Members

Properties properties

Got questions?

We’re always happy to help with code or other questions you might have.