StereoDepth.hpp
Go to the documentation of this file.
1 #pragma once
2 
4 
5 // shared
8 
9 namespace dai {
10 namespace node {
11 
15 class StereoDepth : public NodeCRTP<Node, StereoDepth, StereoDepthProperties> {
16  public:
17  constexpr static const char* NAME = "StereoDepth";
18 
22  enum class PresetMode : std::uint32_t {
26  HIGH_ACCURACY [[deprecated("Will be removed in future releases and replaced with DEFAULT")]],
30  HIGH_DENSITY [[deprecated("Will be removed in future releases and replaced with DEFAULT")]],
31 
32  DEFAULT,
33  FACE,
35  ROBOTICS
36  };
37 
38  protected:
40 
41  private:
43  std::shared_ptr<RawStereoDepthConfig> rawConfig;
44 
45  public:
46  StereoDepth(const std::shared_ptr<PipelineImpl>& par, int64_t nodeId);
47  StereoDepth(const std::shared_ptr<PipelineImpl>& par, int64_t nodeId, std::unique_ptr<Properties> props);
48 
53 
58  Input inputConfig{*this, "inputConfig", Input::Type::SReceiver, false, 4, {{DatatypeEnum::StereoDepthConfig, false}}};
59 
65  Input left{*this, "left", Input::Type::SReceiver, false, 8, true, {{DatatypeEnum::ImgFrame, true}}};
66 
72  Input right{*this, "right", Input::Type::SReceiver, false, 8, true, {{DatatypeEnum::ImgFrame, true}}};
73 
79  Output depth{*this, "depth", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};
80 
90  Output disparity{*this, "disparity", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};
91 
95  Output syncedLeft{*this, "syncedLeft", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};
96 
100  Output syncedRight{*this, "syncedRight", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};
101 
105  Output rectifiedLeft{*this, "rectifiedLeft", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};
106 
110  Output rectifiedRight{*this, "rectifiedRight", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};
111 
115  Output outConfig{*this, "outConfig", Output::Type::MSender, {{DatatypeEnum::StereoDepthConfig, false}}};
116 
121  Output debugDispLrCheckIt1{*this, "debugDispLrCheckIt1", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};
122 
127  Output debugDispLrCheckIt2{*this, "debugDispLrCheckIt2", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};
128 
133  Output debugExtDispLrCheckIt1{*this, "debugExtDispLrCheckIt1", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};
134 
139  Output debugExtDispLrCheckIt2{*this, "debugExtDispLrCheckIt2", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};
140 
145  Output debugDispCostDump{*this, "debugDispCostDump", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};
146 
152  Output confidenceMap{*this, "confidenceMap", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};
153 
158  [[deprecated("Use 'Stereo::setRectification(false)' instead")]] void setEmptyCalibration();
159 
174  void loadMeshFiles(const dai::Path& pathLeft, const dai::Path& pathRight);
175 
181  void loadMeshData(const std::vector<std::uint8_t>& dataLeft, const std::vector<std::uint8_t>& dataRight);
182 
186  void setMeshStep(int width, int height);
187 
193  void setInputResolution(int width, int height);
194 
200  void setInputResolution(std::tuple<int, int> resolution);
201 
207  void setOutputSize(int width, int height);
208 
213  void setOutputKeepAspectRatio(bool keep);
214 
218  [[deprecated("Use 'initialConfig.setMedianFilter()' instead")]] void setMedianFilter(dai::MedianFilter median);
219 
225 
229  void setDepthAlign(CameraBoardSocket camera);
230 
235  [[deprecated("Use 'initialConfig.setConfidenceThreshold()' instead")]] void setConfidenceThreshold(int confThr);
236 
240  void setRectification(bool enable);
241 
247  void setLeftRightCheck(bool enable);
248 
254  void setSubpixel(bool enable);
255 
263  void setSubpixelFractionalBits(int subpixelFractionalBits);
264 
270  void setExtendedDisparity(bool enable);
271 
276  void setRectifyEdgeFillColor(int color);
277 
290  [[deprecated("Function call should be removed")]] void setRectifyMirrorFrame(bool enable);
291 
296  [[deprecated("Function call should be removed")]] void setOutputRectified(bool enable);
297 
303  [[deprecated("Function call should be removed")]] void setOutputDepth(bool enable);
304 
309  void setRuntimeModeSwitch(bool enable);
310 
315  void setNumFramesPool(int numFramesPool);
316 
321  [[deprecated("Use 'initialConfig.getMaxDisparity()' instead")]] float getMaxDisparity() const;
322 
329  void setPostProcessingHardwareResources(int numShaves, int numMemorySlices);
330 
336 
341  [[deprecated("setFocalLengthFromCalibration is deprecated. Default value is true.")]] void setFocalLengthFromCalibration(bool focalLengthFromCalibration);
342 
354 
359 
365  void setBaseline(float baseline);
366 
372  void setFocalLength(float focalLength);
373 
378  void setDisparityToDepthUseSpecTranslation(bool specTranslation);
379 
385  void setRectificationUseSpecTranslation(bool specTranslation);
386 
391  void setDepthAlignmentUseSpecTranslation(bool specTranslation);
392 
400  void setAlphaScaling(float alpha);
401 };
402 
403 } // namespace node
404 } // namespace dai
dai::node::StereoDepth::confidenceMap
Output confidenceMap
Definition: StereoDepth.hpp:152
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::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::node::StereoDepth
StereoDepth node. Compute stereo disparity and depth from left-right image pair.
Definition: StereoDepth.hpp:15
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::StereoDepth::debugDispLrCheckIt1
Output debugDispLrCheckIt1
Definition: StereoDepth.hpp:121
dai::node::StereoDepth::setOutputRectified
void setOutputRectified(bool enable)
Definition: StereoDepth.cpp:144
dai::CameraBoardSocket
CameraBoardSocket
Definition: shared/depthai-shared/include/depthai-shared/common/CameraBoardSocket.hpp:9
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::node::StereoDepth::setDepthAlignmentUseSpecTranslation
void setDepthAlignmentUseSpecTranslation(bool specTranslation)
Definition: StereoDepth.cpp:198
dai::node::StereoDepth::setMedianFilter
void setMedianFilter(dai::MedianFilter median)
Definition: StereoDepth.cpp:102
dai::node::StereoDepth::setRectification
void setRectification(bool enable)
Definition: StereoDepth.cpp:118
dai::node::StereoDepth::NAME
constexpr static const char * NAME
Definition: StereoDepth.hpp:17
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::NodeCRTP
Definition: Node.hpp:342
dai::node::StereoDepth::setFocalLengthFromCalibration
void setFocalLengthFromCalibration(bool focalLengthFromCalibration)
Definition: StereoDepth.cpp:170
dai::node::StereoDepth::setRectificationUseSpecTranslation
void setRectificationUseSpecTranslation(bool specTranslation)
Definition: StereoDepth.cpp:194
dai::node::StereoDepth::debugDispLrCheckIt2
Output debugDispLrCheckIt2
Definition: StereoDepth.hpp:127
dai::node::StereoDepth::PresetMode
PresetMode
Definition: StereoDepth.hpp:22
dai::node::StereoDepth::PresetMode::HIGH_DETAIL
@ HIGH_DETAIL
dai::node::StereoDepth::setRectifyMirrorFrame
void setRectifyMirrorFrame(bool enable)
Definition: StereoDepth.cpp:140
dai::node::StereoDepth::setFocalLength
void setFocalLength(float focalLength)
Definition: StereoDepth.cpp:186
dai::node::StereoDepth::setPostProcessingHardwareResources
void setPostProcessingHardwareResources(int numShaves, int numMemorySlices)
Definition: StereoDepth.cpp:165
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::node::StereoDepth::setMeshStep
void setMeshStep(int width, int height)
Definition: StereoDepth.cpp:83
dai::node::StereoDepth::useHomographyRectification
void useHomographyRectification(bool useHomographyRectification)
Definition: StereoDepth.cpp:174
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::Node::Input
Definition: Node.hpp:147
dai::DatatypeEnum::StereoDepthConfig
@ StereoDepthConfig
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::node::StereoDepth::setBaseline
void setBaseline(float baseline)
Definition: StereoDepth.cpp:182
dai::node::StereoDepth::debugDispCostDump
Output debugDispCostDump
Definition: StereoDepth.hpp:145
dai::Properties
Base Properties structure.
Definition: Properties.hpp:8
dai::node::StereoDepth::outConfig
Output outConfig
Definition: StereoDepth.hpp:115
dai::node::StereoDepth::debugExtDispLrCheckIt2
Output debugExtDispLrCheckIt2
Definition: StereoDepth.hpp:139
StereoDepthConfig.hpp
StereoDepthProperties.hpp
dai::node::StereoDepth::rawConfig
std::shared_ptr< RawStereoDepthConfig > rawConfig
Definition: StereoDepth.hpp:43
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
dai::StereoDepthConfig
Definition: StereoDepthConfig.hpp:14
dai::node::StereoDepth::disparity
Output disparity
Definition: StereoDepth.hpp:90
dai::StereoDepthProperties::DepthAlign
dai::RawStereoDepthConfig::AlgorithmControl::DepthAlign DepthAlign
Definition: StereoDepthProperties.hpp:47
dai::node::StereoDepth::setEmptyCalibration
void setEmptyCalibration()
Definition: StereoDepth.cpp:42
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::DatatypeEnum::ImgFrame
@ ImgFrame
dai::node::StereoDepth::setRuntimeModeSwitch
void setRuntimeModeSwitch(bool enable)
Definition: StereoDepth.cpp:153
dai::node::StereoDepth::inputConfig
Input inputConfig
Definition: StereoDepth.hpp:58
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
Node.hpp
dai::node::StereoDepth::setOutputKeepAspectRatio
void setOutputKeepAspectRatio(bool keep)
Definition: StereoDepth.cpp:99
dai::node::StereoDepth::setNumFramesPool
void setNumFramesPool(int numFramesPool)
Definition: StereoDepth.cpp:157


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