Classes | Public Types | Public Attributes | Static Public Attributes | List of all members
dai::StereoDepthProperties Struct Reference

#include <StereoDepthProperties.hpp>

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

Classes

struct  RectificationMesh
 

Public Types

using DepthAlign = dai::RawStereoDepthConfig::AlgorithmControl::DepthAlign
 
using MedianFilter = dai::MedianFilter
 

Public Attributes

tl::optional< float > alphaScaling
 
tl::optional< float > baseline
 
CameraBoardSocket depthAlignCamera = CameraBoardSocket::AUTO
 
tl::optional< bool > depthAlignmentUseSpecTranslation = tl::nullopt
 
tl::optional< bool > disparityToDepthUseSpecTranslation = tl::nullopt
 
bool enableRectification = true
 
bool enableRuntimeStereoModeSwitch = false
 
tl::optional< float > focalLength
 
bool focalLengthFromCalibration = true
 
tl::optional< std::int32_t > height
 
RawStereoDepthConfig initialConfig
 Initial stereo config. More...
 
RectificationMesh mesh
 
int numFramesPool = 3
 Num frames in output pool. More...
 
std::int32_t numPostProcessingMemorySlices = AUTO
 
std::int32_t numPostProcessingShaves = AUTO
 
tl::optional< std::int32_t > outHeight
 
bool outKeepAspectRatio = true
 
tl::optional< std::int32_t > outWidth
 
tl::optional< bool > rectificationUseSpecTranslation = tl::nullopt
 
std::int32_t rectifyEdgeFillColor = 0
 
tl::optional< bool > useHomographyRectification
 
tl::optional< std::int32_t > width
 

Static Public Attributes

static constexpr const std::int32_t AUTO = -1
 

Additional Inherited Members

- Public Member Functions inherited from dai::PropertiesSerializable< Properties, StereoDepthProperties >
virtual std::unique_ptr< Propertiesclone () const override
 
virtual void serialize (std::vector< std::uint8_t > &data, SerializationType type=SerializationType::LIBNOP) const override
 
- Public Member Functions inherited from dai::Properties
virtual std::unique_ptr< Propertiesclone () const =0
 
virtual ~Properties ()=default
 

Detailed Description

Specify properties for StereoDepth

Definition at line 14 of file StereoDepthProperties.hpp.

Member Typedef Documentation

◆ DepthAlign

Definition at line 47 of file StereoDepthProperties.hpp.

◆ MedianFilter

Definition at line 45 of file StereoDepthProperties.hpp.

Member Data Documentation

◆ alphaScaling

tl::optional<float> dai::StereoDepthProperties::alphaScaling

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 184 of file StereoDepthProperties.hpp.

◆ AUTO

constexpr const std::int32_t dai::StereoDepthProperties::AUTO = -1
staticconstexpr

Definition at line 15 of file StereoDepthProperties.hpp.

◆ baseline

tl::optional<float> dai::StereoDepthProperties::baseline

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

Definition at line 149 of file StereoDepthProperties.hpp.

◆ depthAlignCamera

CameraBoardSocket dai::StereoDepthProperties::depthAlignCamera = CameraBoardSocket::AUTO

Which camera to align disparity/depth to. When configured (not AUTO), takes precedence over 'depthAlign'

Definition at line 53 of file StereoDepthProperties.hpp.

◆ depthAlignmentUseSpecTranslation

tl::optional<bool> dai::StereoDepthProperties::depthAlignmentUseSpecTranslation = tl::nullopt

Use baseline information for depth alignment from specs (design data) or from calibration. Suitable for debugging. Utilizes calibrated value as default

Definition at line 175 of file StereoDepthProperties.hpp.

◆ disparityToDepthUseSpecTranslation

tl::optional<bool> dai::StereoDepthProperties::disparityToDepthUseSpecTranslation = tl::nullopt

Use baseline information for disparity to depth conversion from specs (design data) or from calibration. Suitable for debugging. Utilizes calibrated value as default

Definition at line 162 of file StereoDepthProperties.hpp.

◆ enableRectification

bool dai::StereoDepthProperties::enableRectification = true

Enable stereo rectification/dewarp or not. Useful to disable when replaying pre-recorded rectified frames.

Definition at line 59 of file StereoDepthProperties.hpp.

◆ enableRuntimeStereoModeSwitch

bool dai::StereoDepthProperties::enableRuntimeStereoModeSwitch = false

Whether to enable switching stereo modes at runtime or not. E.g. standard to subpixel, standard+LR-check to subpixel + LR-check. Note: It will allocate resources for worst cases scenario, should be enabled only if dynamic mode switch is required. Default value: false.

Definition at line 99 of file StereoDepthProperties.hpp.

◆ focalLength

tl::optional<float> dai::StereoDepthProperties::focalLength

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

Definition at line 156 of file StereoDepthProperties.hpp.

◆ focalLengthFromCalibration

bool dai::StereoDepthProperties::focalLengthFromCalibration = true

Whether to use horizontal focal length from calibration intrinsics (fx) or calculate based on calibration FOV. Default value is true. If set to false it's calculated from FOV and image resolution: focalLength = calib.width / (2.f * tan(calib.fov / 2 / 180.f * pi));

Definition at line 130 of file StereoDepthProperties.hpp.

◆ height

tl::optional<std::int32_t> dai::StereoDepthProperties::height

Input frame height. Optional (taken from MonoCamera nodes if they exist)

Definition at line 72 of file StereoDepthProperties.hpp.

◆ initialConfig

RawStereoDepthConfig dai::StereoDepthProperties::initialConfig

Initial stereo config.

Definition at line 43 of file StereoDepthProperties.hpp.

◆ mesh

RectificationMesh dai::StereoDepthProperties::mesh

Specify a direct warp mesh to be used for rectification, instead of intrinsics + extrinsic matrices

Definition at line 90 of file StereoDepthProperties.hpp.

◆ numFramesPool

int dai::StereoDepthProperties::numFramesPool = 3

Num frames in output pool.

Definition at line 102 of file StereoDepthProperties.hpp.

◆ numPostProcessingMemorySlices

std::int32_t dai::StereoDepthProperties::numPostProcessingMemorySlices = AUTO

Number of memory slices reserved for stereo depth post processing. -1 means auto, memory will be allocated based on initial stereo settings and number of shaves. 0 means that it will reuse the memory slices assigned for main stereo algorithm. For optimal performance it's recommended to allocate more than 0, so post processing will run in parallel with main stereo algorithm. Minimum 1, maximum 6.

Definition at line 123 of file StereoDepthProperties.hpp.

◆ numPostProcessingShaves

std::int32_t dai::StereoDepthProperties::numPostProcessingShaves = AUTO

Number of shaves reserved for stereo depth post processing. Post processing can use multiple shaves to increase performance. -1 means auto, resources will be allocated based on enabled filters. 0 means that it will reuse the shave assigned for main stereo algorithm. For optimal performance it's recommended to allocate more than 0, so post processing will run in parallel with main stereo algorithm. Minimum 1, maximum 10.

Definition at line 113 of file StereoDepthProperties.hpp.

◆ outHeight

tl::optional<std::int32_t> dai::StereoDepthProperties::outHeight

Output disparity/depth height. Currently only used when aligning to RGB

Definition at line 80 of file StereoDepthProperties.hpp.

◆ outKeepAspectRatio

bool dai::StereoDepthProperties::outKeepAspectRatio = true

Whether to keep aspect ratio of the input (rectified) or not

Definition at line 84 of file StereoDepthProperties.hpp.

◆ outWidth

tl::optional<std::int32_t> dai::StereoDepthProperties::outWidth

Output disparity/depth width. Currently only used when aligning to RGB

Definition at line 76 of file StereoDepthProperties.hpp.

◆ rectificationUseSpecTranslation

tl::optional<bool> dai::StereoDepthProperties::rectificationUseSpecTranslation = tl::nullopt

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

Definition at line 169 of file StereoDepthProperties.hpp.

◆ rectifyEdgeFillColor

std::int32_t dai::StereoDepthProperties::rectifyEdgeFillColor = 0

Fill color for missing data at frame edges - grayscale 0..255, or -1 to replicate pixels

Definition at line 64 of file StereoDepthProperties.hpp.

◆ useHomographyRectification

tl::optional<bool> dai::StereoDepthProperties::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. 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.

Definition at line 142 of file StereoDepthProperties.hpp.

◆ width

tl::optional<std::int32_t> dai::StereoDepthProperties::width

Input frame width. Optional (taken from MonoCamera nodes if they exist)

Definition at line 68 of file StereoDepthProperties.hpp.


The documentation for this struct was generated from the following file:


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