StereoDepth.cpp
Go to the documentation of this file.
2 
3 // standard
4 #include <fstream>
5 
6 #include "spdlog/spdlog.h"
7 #include "utility/Logging.hpp"
8 #include "utility/spdlog-fmt.hpp"
9 
10 namespace dai {
11 namespace node {
12 
13 StereoDepth::StereoDepth(const std::shared_ptr<PipelineImpl>& par, int64_t nodeId) : StereoDepth(par, nodeId, std::make_unique<StereoDepth::Properties>()) {}
14 StereoDepth::StereoDepth(const std::shared_ptr<PipelineImpl>& par, int64_t nodeId, std::unique_ptr<Properties> props)
15  : NodeCRTP<Node, StereoDepth, StereoDepthProperties>(par, nodeId, std::move(props)),
16  rawConfig(std::make_shared<RawStereoDepthConfig>()),
17  initialConfig(rawConfig) {
18  // 'properties' defaults already set
21  &disparity,
22  &syncedLeft,
23  &syncedRight,
26  &outConfig,
32  &confidenceMap});
33 
35 }
36 
39  return properties;
40 }
41 
43  setRectification(false);
44  logger::warn("{} is deprecated. This function call can be replaced by Stereo::setRectification(false). ", __func__);
45 }
46 
47 void StereoDepth::loadMeshData(const std::vector<std::uint8_t>& dataLeft, const std::vector<std::uint8_t>& dataRight) {
48  if(dataLeft.size() != dataRight.size()) {
49  throw std::runtime_error("StereoDepth | left and right mesh sizes must match");
50  }
51 
52  Asset meshAsset;
53  std::string assetKey;
54  meshAsset.alignment = 64;
55 
56  meshAsset.data = dataLeft;
57  assetKey = "meshLeft";
58  properties.mesh.meshLeftUri = assetManager.set(assetKey, meshAsset)->getRelativeUri();
59 
60  meshAsset.data = dataRight;
61  assetKey = "meshRight";
62  properties.mesh.meshRightUri = assetManager.set(assetKey, meshAsset)->getRelativeUri();
63 
64  properties.mesh.meshSize = static_cast<uint32_t>(meshAsset.data.size());
65 }
66 
67 void StereoDepth::loadMeshFiles(const dai::Path& pathLeft, const dai::Path& pathRight) {
68  std::ifstream streamLeft(pathLeft, std::ios::binary);
69  if(!streamLeft.is_open()) {
70  throw std::runtime_error(fmt::format("StereoDepth | Cannot open mesh at path: {}", pathLeft));
71  }
72  std::vector<std::uint8_t> dataLeft = std::vector<std::uint8_t>(std::istreambuf_iterator<char>(streamLeft), {});
73 
74  std::ifstream streamRight(pathRight, std::ios::binary);
75  if(!streamRight.is_open()) {
76  throw std::runtime_error(fmt::format("StereoDepth | Cannot open mesh at path: {}", pathRight));
77  }
78  std::vector<std::uint8_t> dataRight = std::vector<std::uint8_t>(std::istreambuf_iterator<char>(streamRight), {});
79 
80  loadMeshData(dataLeft, dataRight);
81 }
82 
83 void StereoDepth::setMeshStep(int width, int height) {
84  properties.mesh.stepWidth = width;
85  properties.mesh.stepHeight = height;
86 }
87 
88 void StereoDepth::setInputResolution(int width, int height) {
89  properties.width = width;
90  properties.height = height;
91 }
92 void StereoDepth::setInputResolution(std::tuple<int, int> resolution) {
93  setInputResolution(std::get<0>(resolution), std::get<1>(resolution));
94 }
95 void StereoDepth::setOutputSize(int width, int height) {
96  properties.outWidth = width;
97  properties.outHeight = height;
98 }
101 }
105 }
106 void StereoDepth::setDepthAlign(Properties::DepthAlign align) {
108  // Unset 'depthAlignCamera', that would take precedence otherwise
110 }
112  properties.depthAlignCamera = camera;
113 }
117 }
118 void StereoDepth::setRectification(bool enable) {
120 }
124 }
125 void StereoDepth::setSubpixel(bool enable) {
126  initialConfig.setSubpixel(enable);
128 }
129 void StereoDepth::setSubpixelFractionalBits(int subpixelFractionalBits) {
130  initialConfig.setSubpixelFractionalBits(subpixelFractionalBits);
132 }
136 }
139 }
141  (void)enable;
142  logger::warn("{} is deprecated.", __func__);
143 }
145  (void)enable;
146  logger::warn("{} is deprecated. The output is auto-enabled if used", __func__);
147 }
148 void StereoDepth::setOutputDepth(bool enable) {
149  (void)enable;
150  logger::warn("{} is deprecated. The output is auto-enabled if used", __func__);
151 }
152 
155 }
156 
157 void StereoDepth::setNumFramesPool(int numFramesPool) {
158  properties.numFramesPool = numFramesPool;
159 }
160 
163 }
164 
165 void StereoDepth::setPostProcessingHardwareResources(int numShaves, int numMemorySlices) {
167  properties.numPostProcessingMemorySlices = numMemorySlices;
168 }
169 
170 void StereoDepth::setFocalLengthFromCalibration(bool focalLengthFromCalibration) {
171  properties.focalLengthFromCalibration = focalLengthFromCalibration;
172 }
173 
174 void StereoDepth::useHomographyRectification(bool useHomographyRectification) {
176 }
177 
178 void StereoDepth::enableDistortionCorrection(bool enableDistortionCorrection) {
180 }
181 
182 void StereoDepth::setBaseline(float baseline) {
183  properties.baseline = baseline;
184 }
185 
186 void StereoDepth::setFocalLength(float focalLength) {
187  properties.focalLength = focalLength;
188 }
189 
192 }
193 
196 }
197 
200 }
201 
202 void StereoDepth::setAlphaScaling(float alpha) {
203  properties.alphaScaling = alpha;
204 }
205 
207  presetMode = mode;
208  switch(presetMode) {
213  } break;
218  } break;
219  case PresetMode::DEFAULT: {
226 
228 
236 
237  config.postProcessing.spatialFilter.enable = true;
240  config.postProcessing.spatialFilter.alpha = 0.5;
242 
243  config.postProcessing.temporalFilter.enable = true;
244  config.postProcessing.temporalFilter.alpha = 0.5;
246 
247  config.postProcessing.speckleFilter.enable = true;
250 
252  config.postProcessing.thresholdFilter.maxRange = 15000;
253 
254  initialConfig.set(config);
255 
257  } break;
258  case PresetMode::FACE: {
265 
267 
275 
276  config.postProcessing.spatialFilter.enable = true;
279  config.postProcessing.spatialFilter.alpha = 0.5;
281 
282  config.postProcessing.temporalFilter.enable = true;
283  config.postProcessing.temporalFilter.alpha = 0.5;
285 
286  config.postProcessing.speckleFilter.enable = true;
289 
292 
293  initialConfig.set(config);
294 
296  } break;
304 
306 
314 
315  config.postProcessing.spatialFilter.enable = true;
318  config.postProcessing.spatialFilter.alpha = 0.5;
320 
321  config.postProcessing.temporalFilter.enable = true;
322  config.postProcessing.temporalFilter.alpha = 0.5;
324 
325  config.postProcessing.speckleFilter.enable = true;
328 
330  config.postProcessing.thresholdFilter.maxRange = 15000;
331 
332  initialConfig.set(config);
333 
335  } break;
336  case PresetMode::ROBOTICS: {
343 
345 
353 
354  config.postProcessing.spatialFilter.enable = true;
357  config.postProcessing.spatialFilter.alpha = 0.5;
358  config.postProcessing.spatialFilter.delta = 20;
359 
360  config.postProcessing.temporalFilter.enable = false;
361  config.postProcessing.temporalFilter.alpha = 0.5;
363 
364  config.postProcessing.speckleFilter.enable = true;
367 
369  config.postProcessing.thresholdFilter.maxRange = 10000;
370 
371  initialConfig.set(config);
372 
374  } break;
375  }
376 }
377 
378 } // namespace node
379 } // namespace dai
dai::NodeCRTP< Node, StereoDepth, StereoDepthProperties >::properties
Properties & properties
Underlying properties.
Definition: Node.hpp:346
dai::StereoDepthProperties::RectificationMesh::stepHeight
uint16_t stepHeight
Definition: StereoDepthProperties.hpp:37
dai::StereoDepthConfig::setSubpixelFractionalBits
StereoDepthConfig & setSubpixelFractionalBits(int subpixelFractionalBits)
Definition: StereoDepthConfig.cpp:69
dai::CameraBoardSocket::AUTO
@ AUTO
dai::node::StereoDepth::confidenceMap
Output confidenceMap
Definition: StereoDepth.hpp:152
dai::RawStereoDepthConfig::PostProcessing::SpatialFilter::enable
bool enable
Definition: RawStereoDepthConfig.hpp:162
dai::node::StereoDepth::depth
Output depth
Definition: StereoDepth.hpp:79
dai::node::StereoDepth::setSubpixel
void setSubpixel(bool enable)
Definition: StereoDepth.cpp:125
dai::node::StereoDepth::setOutputSize
void setOutputSize(int width, int height)
Definition: StereoDepth.cpp:95
dai::RawStereoDepthConfig::PostProcessing::filteringOrder
std::array< Filter, 5 > filteringOrder
Definition: RawStereoDepthConfig.hpp:140
dai::node::StereoDepth::initialConfig
StereoDepthConfig initialConfig
Definition: StereoDepth.hpp:52
dai::node::StereoDepth::PresetMode::HIGH_ACCURACY
@ HIGH_ACCURACY
dai::node::StereoDepth::setSubpixelFractionalBits
void setSubpixelFractionalBits(int subpixelFractionalBits)
Definition: StereoDepth.cpp:129
dai::node::StereoDepth::enableDistortionCorrection
void enableDistortionCorrection(bool enableDistortionCorrection)
Definition: StereoDepth.cpp:178
dai::node::StereoDepth::rectifiedLeft
Output rectifiedLeft
Definition: StereoDepth.hpp:105
dai::RawStereoDepthConfig::PostProcessing::Filter::SPECKLE
@ SPECKLE
dai::node::StereoDepth
StereoDepth node. Compute stereo disparity and depth from left-right image pair.
Definition: StereoDepth.hpp:15
dai::Asset::alignment
std::uint32_t alignment
Definition: AssetManager.hpp:20
dai::StereoDepthProperties::height
tl::optional< std::int32_t > height
Definition: StereoDepthProperties.hpp:72
dai::node::StereoDepth::StereoDepth
StereoDepth(const std::shared_ptr< PipelineImpl > &par, int64_t nodeId)
Definition: StereoDepth.cpp:13
dai::node::StereoDepth::setDefaultProfilePreset
void setDefaultProfilePreset(PresetMode mode)
Definition: StereoDepth.cpp:206
dai::MedianFilter
MedianFilter
Definition: MedianFilter.hpp:14
dai::Node::setInputRefs
void setInputRefs(std::initializer_list< Input * > l)
dai::RawStereoDepthConfig::PostProcessing::speckleFilter
SpeckleFilter speckleFilter
Definition: RawStereoDepthConfig.hpp:335
dai::node::StereoDepth::debugDispLrCheckIt1
Output debugDispLrCheckIt1
Definition: StereoDepth.hpp:121
dai::RawStereoDepthConfig::postProcessing
PostProcessing postProcessing
Definition: RawStereoDepthConfig.hpp:385
dai::node::StereoDepth::setOutputRectified
void setOutputRectified(bool enable)
Definition: StereoDepth.cpp:144
dai::StereoDepthConfig::set
StereoDepthConfig & set(dai::RawStereoDepthConfig config)
Definition: StereoDepthConfig.cpp:151
dai::StereoDepthProperties::useHomographyRectification
tl::optional< bool > useHomographyRectification
Definition: StereoDepthProperties.hpp:142
dai::Node
Abstract Node.
Definition: Node.hpp:29
dai::StereoDepthProperties::alphaScaling
tl::optional< float > alphaScaling
Definition: StereoDepthProperties.hpp:184
dai::RawStereoDepthConfig::PostProcessing::SpeckleFilter::speckleRange
std::uint32_t speckleRange
Definition: RawStereoDepthConfig.hpp:320
dai::RawStereoDepthConfig::PostProcessing::DecimationFilter::DecimationMode::PIXEL_SKIPPING
@ PIXEL_SKIPPING
dai::RawStereoDepthConfig::PostProcessing::Filter::DECIMATION
@ DECIMATION
dai::StereoDepthConfig::setConfidenceThreshold
StereoDepthConfig & setConfidenceThreshold(int confThr)
Definition: StereoDepthConfig.cpp:18
dai::StereoDepthProperties::focalLength
tl::optional< float > focalLength
Definition: StereoDepthProperties.hpp:156
dai::StereoDepthProperties::outKeepAspectRatio
bool outKeepAspectRatio
Definition: StereoDepthProperties.hpp:84
dai::RawStereoDepthConfig::PostProcessing::TemporalFilter::delta
std::int32_t delta
Definition: RawStereoDepthConfig.hpp:244
dai::CameraBoardSocket
CameraBoardSocket
Definition: shared/depthai-shared/include/depthai-shared/common/CameraBoardSocket.hpp:9
dai::MedianFilter::MEDIAN_OFF
@ MEDIAN_OFF
dai::RawStereoDepthConfig::PostProcessing::temporalFilter
TemporalFilter temporalFilter
Definition: RawStereoDepthConfig.hpp:252
dai::node::StereoDepth::PresetMode::DEFAULT
@ DEFAULT
dai::node::StereoDepth::rectifiedRight
Output rectifiedRight
Definition: StereoDepth.hpp:110
dai::node::StereoDepth::getMaxDisparity
float getMaxDisparity() const
Definition: StereoDepth.cpp:161
dai::RawStereoDepthConfig::PostProcessing::SpatialFilter::numIterations
std::int32_t numIterations
Definition: RawStereoDepthConfig.hpp:189
dai::node::StereoDepth::setDepthAlignmentUseSpecTranslation
void setDepthAlignmentUseSpecTranslation(bool specTranslation)
Definition: StereoDepth.cpp:198
dai::StereoDepthConfig::setExtendedDisparity
StereoDepthConfig & setExtendedDisparity(bool enable)
Definition: StereoDepthConfig.cpp:59
dai::node::StereoDepth::setMedianFilter
void setMedianFilter(dai::MedianFilter median)
Definition: StereoDepth.cpp:102
dai::StereoDepthProperties::width
tl::optional< std::int32_t > width
Definition: StereoDepthProperties.hpp:68
dai::Node::assetManager
AssetManager assetManager
Definition: Node.hpp:291
dai::Asset::data
std::vector< std::uint8_t > data
Definition: AssetManager.hpp:19
dai::StereoDepthProperties::RectificationMesh::meshRightUri
std::string meshRightUri
Definition: StereoDepthProperties.hpp:25
dai::node::StereoDepth::setRectification
void setRectification(bool enable)
Definition: StereoDepth.cpp:118
dai::node::StereoDepth::setDepthAlign
void setDepthAlign(Properties::DepthAlign align)
Definition: StereoDepth.cpp:106
dai::node::StereoDepth::setLeftRightCheck
void setLeftRightCheck(bool enable)
Definition: StereoDepth.cpp:121
dai::logger::warn
void warn(const FormatString &fmt, Args &&...args)
Definition: Logging.hpp:84
dai::NodeCRTP
Definition: Node.hpp:342
dai::StereoDepthConfig::setDepthAlign
StereoDepthConfig & setDepthAlign(AlgorithmControl::DepthAlign align)
Definition: StereoDepthConfig.cpp:13
dai::node::StereoDepth::setFocalLengthFromCalibration
void setFocalLengthFromCalibration(bool focalLengthFromCalibration)
Definition: StereoDepth.cpp:170
dai::StereoDepthProperties::numPostProcessingMemorySlices
std::int32_t numPostProcessingMemorySlices
Definition: StereoDepthProperties.hpp:123
dai::node::StereoDepth::setRectificationUseSpecTranslation
void setRectificationUseSpecTranslation(bool specTranslation)
Definition: StereoDepth.cpp:194
dai::StereoDepthProperties::mesh
RectificationMesh mesh
Definition: StereoDepthProperties.hpp:90
dai::node::StereoDepth::debugDispLrCheckIt2
Output debugDispLrCheckIt2
Definition: StereoDepth.hpp:127
dai::StereoDepthProperties
Definition: StereoDepthProperties.hpp:14
dai::node::StereoDepth::PresetMode
PresetMode
Definition: StereoDepth.hpp:22
dai::StereoDepthConfig::setLeftRightCheck
StereoDepthConfig & setLeftRightCheck(bool enable)
Definition: StereoDepthConfig.cpp:54
dai::node::StereoDepth::PresetMode::HIGH_DETAIL
@ HIGH_DETAIL
dai::node::StereoDepth::setRectifyMirrorFrame
void setRectifyMirrorFrame(bool enable)
Definition: StereoDepth.cpp:140
dai::RawStereoDepthConfig::PostProcessing::SpatialFilter::alpha
float alpha
Definition: RawStereoDepthConfig.hpp:175
dai::RawStereoDepthConfig::PostProcessing::decimationFilter
DecimationFilter decimationFilter
Definition: RawStereoDepthConfig.hpp:368
dai::node::StereoDepth::setFocalLength
void setFocalLength(float focalLength)
Definition: StereoDepth.cpp:186
dai::RawStereoDepthConfig::PostProcessing::SpeckleFilter::differenceThreshold
std::uint32_t differenceThreshold
Definition: RawStereoDepthConfig.hpp:326
dai::node::StereoDepth::setPostProcessingHardwareResources
void setPostProcessingHardwareResources(int numShaves, int numMemorySlices)
Definition: StereoDepth.cpp:165
dai::RawStereoDepthConfig::PostProcessing::spatialFilter
SpatialFilter spatialFilter
Definition: RawStereoDepthConfig.hpp:197
dai::node::StereoDepth::setAlphaScaling
void setAlphaScaling(float alpha)
Definition: StereoDepth.cpp:202
dai::node::StereoDepth::syncedLeft
Output syncedLeft
Definition: StereoDepth.hpp:95
dai::node::StereoDepth::left
Input left
Definition: StereoDepth.hpp:65
dai::node::StereoDepth::PresetMode::FACE
@ FACE
dai::StereoDepthProperties::depthAlignCamera
CameraBoardSocket depthAlignCamera
Definition: StereoDepthProperties.hpp:53
dai::Asset
Asset is identified with string key and can store arbitrary binary data.
Definition: AssetManager.hpp:15
dai::node::StereoDepth::setMeshStep
void setMeshStep(int width, int height)
Definition: StereoDepth.cpp:83
dai::StereoDepthConfig::setSubpixel
StereoDepthConfig & setSubpixel(bool enable)
Definition: StereoDepthConfig.cpp:64
dai::RawStereoDepthConfig::PostProcessing::Filter::MEDIAN
@ MEDIAN
dai::node::StereoDepth::useHomographyRectification
void useHomographyRectification(bool useHomographyRectification)
Definition: StereoDepth.cpp:174
dai::StereoDepthConfig::getMaxDisparity
float getMaxDisparity() const
Definition: StereoDepthConfig.cpp:93
dai::StereoDepthProperties::depthAlignmentUseSpecTranslation
tl::optional< bool > depthAlignmentUseSpecTranslation
Definition: StereoDepthProperties.hpp:175
dai::StereoDepthProperties::focalLengthFromCalibration
bool focalLengthFromCalibration
Definition: StereoDepthProperties.hpp:130
dai::node::StereoDepth::loadMeshFiles
void loadMeshFiles(const dai::Path &pathLeft, const dai::Path &pathRight)
Definition: StereoDepth.cpp:67
dai::node::StereoDepth::PresetMode::ROBOTICS
@ ROBOTICS
dai::node::StereoDepth::setOutputDepth
void setOutputDepth(bool enable)
Definition: StereoDepth.cpp:148
dai::RawStereoDepthConfig::PostProcessing::Filter::TEMPORAL
@ TEMPORAL
dai::AssetManager::set
std::shared_ptr< dai::Asset > set(Asset asset)
Definition: AssetManager.cpp:15
dai::RawStereoDepthConfig::PostProcessing::DecimationFilter::decimationFactor
std::uint32_t decimationFactor
Definition: RawStereoDepthConfig.hpp:347
dai::node::StereoDepth::syncedRight
Output syncedRight
Definition: StereoDepth.hpp:100
dai::node::StereoDepth::setDisparityToDepthUseSpecTranslation
void setDisparityToDepthUseSpecTranslation(bool specTranslation)
Definition: StereoDepth.cpp:190
dai::node::StereoDepth::setRectifyEdgeFillColor
void setRectifyEdgeFillColor(int color)
Definition: StereoDepth.cpp:137
dai::RawStereoDepthConfig::PostProcessing::ThresholdFilter::minRange
std::int32_t minRange
Definition: RawStereoDepthConfig.hpp:263
dai::StereoDepthProperties::baseline
tl::optional< float > baseline
Definition: StereoDepthProperties.hpp:149
dai::node::StereoDepth::setBaseline
void setBaseline(float baseline)
Definition: StereoDepth.cpp:182
dai::StereoDepthProperties::numPostProcessingShaves
std::int32_t numPostProcessingShaves
Definition: StereoDepthProperties.hpp:113
dai::RawStereoDepthConfig::PostProcessing::TemporalFilter::alpha
float alpha
Definition: RawStereoDepthConfig.hpp:235
dai::StereoDepthProperties::RectificationMesh::meshLeftUri
std::string meshLeftUri
Definition: StereoDepthProperties.hpp:21
dai::StereoDepthProperties::RectificationMesh::meshSize
tl::optional< std::uint32_t > meshSize
Definition: StereoDepthProperties.hpp:29
dai::node::StereoDepth::debugDispCostDump
Output debugDispCostDump
Definition: StereoDepth.hpp:145
dai::RawStereoDepthConfig::PostProcessing::DecimationFilter::decimationMode
DecimationMode decimationMode
Definition: RawStereoDepthConfig.hpp:359
dai::RawStereoDepthConfig::PostProcessing::ThresholdFilter::maxRange
std::int32_t maxRange
Definition: RawStereoDepthConfig.hpp:268
dai::Properties
Base Properties structure.
Definition: Properties.hpp:8
dai::StereoDepthProperties::outHeight
tl::optional< std::int32_t > outHeight
Definition: StereoDepthProperties.hpp:80
dai::RawStereoDepthConfig::PostProcessing::SpatialFilter::holeFillingRadius
std::uint8_t holeFillingRadius
Definition: RawStereoDepthConfig.hpp:169
dai::node::StereoDepth::outConfig
Output outConfig
Definition: StereoDepth.hpp:115
dai::node::StereoDepth::debugExtDispLrCheckIt2
Output debugExtDispLrCheckIt2
Definition: StereoDepth.hpp:139
dai::StereoDepthProperties::enableRectification
bool enableRectification
Definition: StereoDepthProperties.hpp:59
dai::node::StereoDepth::rawConfig
std::shared_ptr< RawStereoDepthConfig > rawConfig
Definition: StereoDepth.hpp:43
dai::StereoDepthConfig::setMedianFilter
StereoDepthConfig & setMedianFilter(MedianFilter median)
Definition: StereoDepthConfig.cpp:27
dai::Node::setOutputRefs
void setOutputRefs(std::initializer_list< Output * > l)
dai::node::StereoDepth::getProperties
Properties & getProperties()
Definition: StereoDepth.cpp:37
dai::node::StereoDepth::setInputResolution
void setInputResolution(int width, int height)
Definition: StereoDepth.cpp:88
dai::node::StereoDepth::PresetMode::HIGH_DENSITY
@ HIGH_DENSITY
dai::node::StereoDepth::loadMeshData
void loadMeshData(const std::vector< std::uint8_t > &dataLeft, const std::vector< std::uint8_t > &dataRight)
Definition: StereoDepth.cpp:47
dai::node::StereoDepth::right
Input right
Definition: StereoDepth.hpp:72
dai::node::StereoDepth::setExtendedDisparity
void setExtendedDisparity(bool enable)
Definition: StereoDepth.cpp:133
std
Definition: Node.hpp:366
dai::StereoDepthConfig::setLeftRightCheckThreshold
StereoDepthConfig & setLeftRightCheckThreshold(int threshold)
Definition: StereoDepthConfig.cpp:45
dai::RawStereoDepthConfig::PostProcessing::SpeckleFilter::enable
bool enable
Definition: RawStereoDepthConfig.hpp:316
dai::StereoDepthConfig::get
dai::RawStereoDepthConfig get() const
Definition: StereoDepthConfig.cpp:147
dai::StereoDepthProperties::rectificationUseSpecTranslation
tl::optional< bool > rectificationUseSpecTranslation
Definition: StereoDepthProperties.hpp:169
dai::StereoDepthProperties::rectifyEdgeFillColor
std::int32_t rectifyEdgeFillColor
Definition: StereoDepthProperties.hpp:64
spdlog-fmt.hpp
dai::RawStereoDepthConfig::PostProcessing::thresholdFilter
ThresholdFilter thresholdFilter
Definition: RawStereoDepthConfig.hpp:277
StereoDepth.hpp
dai::RawStereoDepthConfig::PostProcessing::SpatialFilter::delta
std::int32_t delta
Definition: RawStereoDepthConfig.hpp:184
dai::node::StereoDepth::disparity
Output disparity
Definition: StereoDepth.hpp:90
dai::StereoDepthProperties::disparityToDepthUseSpecTranslation
tl::optional< bool > disparityToDepthUseSpecTranslation
Definition: StereoDepthProperties.hpp:162
dai::node::StereoDepth::setEmptyCalibration
void setEmptyCalibration()
Definition: StereoDepth.cpp:42
dai::StereoDepthProperties::numFramesPool
int numFramesPool
Num frames in output pool.
Definition: StereoDepthProperties.hpp:102
dai::MedianFilter::KERNEL_7x7
@ KERNEL_7x7
dai::node::StereoDepth::debugExtDispLrCheckIt1
Output debugExtDispLrCheckIt1
Definition: StereoDepth.hpp:133
dai::Path
Represents paths on a filesystem; accepts utf-8, Windows utf-16 wchar_t, or std::filesystem::path.
Definition: Path.hpp:27
dai::RawStereoDepthConfig
RawStereoDepthConfig configuration structure.
Definition: RawStereoDepthConfig.hpp:14
Logging.hpp
dai::node::StereoDepth::setRuntimeModeSwitch
void setRuntimeModeSwitch(bool enable)
Definition: StereoDepth.cpp:153
dai::node::StereoDepth::inputConfig
Input inputConfig
Definition: StereoDepth.hpp:58
dai::StereoDepthProperties::initialConfig
RawStereoDepthConfig initialConfig
Initial stereo config.
Definition: StereoDepthProperties.hpp:43
dai::StereoDepthProperties::enableRuntimeStereoModeSwitch
bool enableRuntimeStereoModeSwitch
Definition: StereoDepthProperties.hpp:99
dai::node::StereoDepth::setConfidenceThreshold
void setConfidenceThreshold(int confThr)
Definition: StereoDepth.cpp:114
dai::node::StereoDepth::presetMode
PresetMode presetMode
Definition: StereoDepth.hpp:42
dai
Definition: CameraExposureOffset.hpp:6
dai::StereoDepthProperties::outWidth
tl::optional< std::int32_t > outWidth
Definition: StereoDepthProperties.hpp:76
dai::StereoDepthProperties::RectificationMesh::stepWidth
uint16_t stepWidth
Definition: StereoDepthProperties.hpp:33
dai::RawStereoDepthConfig::PostProcessing::TemporalFilter::enable
bool enable
Definition: RawStereoDepthConfig.hpp:208
dai::node::StereoDepth::setOutputKeepAspectRatio
void setOutputKeepAspectRatio(bool keep)
Definition: StereoDepth.cpp:99
dai::node::StereoDepth::setNumFramesPool
void setNumFramesPool(int numFramesPool)
Definition: StereoDepth.cpp:157
dai::RawStereoDepthConfig::PostProcessing::Filter::SPATIAL
@ SPATIAL


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