depth_post_processing.cpp
Go to the documentation of this file.
1 #include <iostream>
2 
3 // Inludes common necessary includes for development using depthai library
4 #include "depthai/depthai.hpp"
5 
6 // Closer-in minimum depth, disparity range is doubled (from 95 to 190):
7 static std::atomic<bool> extended_disparity{false};
8 // Better accuracy for longer distance, fractional disparity 32-levels:
9 static std::atomic<bool> subpixel{false};
10 // Better handling for occlusions:
11 static std::atomic<bool> lr_check{true};
12 
13 int main() {
14  // Create pipeline
15  dai::Pipeline pipeline;
16 
17  // Define sources and outputs
18  auto monoLeft = pipeline.create<dai::node::MonoCamera>();
19  auto monoRight = pipeline.create<dai::node::MonoCamera>();
20  auto depth = pipeline.create<dai::node::StereoDepth>();
21  auto xout = pipeline.create<dai::node::XLinkOut>();
22 
23  xout->setStreamName("disparity");
24 
25  // Properties
27  monoLeft->setCamera("left");
29  monoRight->setCamera("right");
30 
31  // Create a node that will produce the depth map (using disparity output as it's easier to visualize depth this way)
32  depth->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
33  // Options: MEDIAN_OFF, KERNEL_3x3, KERNEL_5x5, KERNEL_7x7 (default)
34  depth->initialConfig.setMedianFilter(dai::MedianFilter::KERNEL_7x7);
35  depth->setLeftRightCheck(lr_check);
36  depth->setExtendedDisparity(extended_disparity);
37  depth->setSubpixel(subpixel);
38  auto config = depth->initialConfig.get();
39  config.postProcessing.speckleFilter.enable = false;
40  config.postProcessing.speckleFilter.speckleRange = 50;
41  config.postProcessing.temporalFilter.enable = true;
42  config.postProcessing.spatialFilter.enable = true;
43  config.postProcessing.spatialFilter.holeFillingRadius = 2;
44  config.postProcessing.spatialFilter.numIterations = 1;
45  config.postProcessing.thresholdFilter.minRange = 400;
46  config.postProcessing.thresholdFilter.maxRange = 15000;
47  config.postProcessing.decimationFilter.decimationFactor = 1;
48  depth->initialConfig.set(config);
49 
50  // Linking
51  monoLeft->out.link(depth->left);
52  monoRight->out.link(depth->right);
53  depth->disparity.link(xout->input);
54 
55  // Connect to device and start pipeline
56  dai::Device device(pipeline);
57 
58  // Output queue will be used to get the disparity frames from the outputs defined above
59  auto q = device.getOutputQueue("disparity", 4, false);
60 
61  while(true) {
62  auto inDepth = q->get<dai::ImgFrame>();
63  auto frame = inDepth->getFrame();
64  // Normalization for better visualization
65  frame.convertTo(frame, CV_8UC1, 255 / depth->initialConfig.getMaxDisparity());
66 
67  cv::imshow("disparity", frame);
68 
69  // Available color maps: https://docs.opencv.org/3.4/d3/d50/group__imgproc__colormap.html
70  cv::applyColorMap(frame, frame, cv::COLORMAP_JET);
71  cv::imshow("disparity_color", frame);
72 
73  int key = cv::waitKey(1);
74  if(key == 'q' || key == 'Q') {
75  return 0;
76  }
77  }
78  return 0;
79 }
dai::node::MonoCamera::out
Output out
Definition: MonoCamera.hpp:47
dai::node::XLinkOut
XLinkOut node. Sends messages over XLink.
Definition: XLinkOut.hpp:14
dai::node::MonoCamera::setCamera
void setCamera(std::string name)
Definition: MonoCamera.cpp:36
dai::Pipeline
Represents the pipeline, set of nodes and connections between them.
Definition: Pipeline.hpp:100
main
int main()
Definition: depth_post_processing.cpp:13
dai::ImgFrame::getFrame
void getFrame(T...)
Definition: ImgFrame.hpp:218
dai::node::StereoDepth
StereoDepth node. Compute stereo disparity and depth from left-right image pair.
Definition: StereoDepth.hpp:15
dai::node::MonoCamera
MonoCamera node. For use with grayscale sensors.
Definition: MonoCamera.hpp:17
dai::Device::getOutputQueue
std::shared_ptr< DataOutputQueue > getOutputQueue(const std::string &name)
Definition: Device.cpp:86
dai::MonoCameraProperties::SensorResolution::THE_400_P
@ THE_400_P
depthai.hpp
dai::Pipeline::create
std::shared_ptr< N > create()
Definition: Pipeline.hpp:145
extended_disparity
static std::atomic< bool > extended_disparity
Definition: depth_post_processing.cpp:7
dai::node::MonoCamera::setResolution
void setResolution(Properties::SensorResolution resolution)
Set sensor resolution.
Definition: MonoCamera.cpp:82
dai::ImgFrame
Definition: ImgFrame.hpp:25
lr_check
static std::atomic< bool > lr_check
Definition: depth_post_processing.cpp:11
dai::node::StereoDepth::PresetMode::HIGH_DENSITY
@ HIGH_DENSITY
subpixel
static std::atomic< bool > subpixel
Definition: depth_post_processing.cpp:9
dai::Device
Definition: Device.hpp:21
dai::MedianFilter::KERNEL_7x7
@ KERNEL_7x7
dai::Node::Output::link
void link(const Input &in)
Definition: Node.cpp:84


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