stereo_depth_video.cpp
Go to the documentation of this file.
1 #include <iostream>
2 
3 // Includes common necessary includes for development using depthai library
4 #include "depthai/depthai.hpp"
5 
6 static std::atomic<bool> withDepth{true};
7 
8 static std::atomic<bool> outputDepth{false};
9 static std::atomic<bool> outputRectified{true};
10 static std::atomic<bool> lrcheck{true};
11 static std::atomic<bool> extended{false};
12 static std::atomic<bool> subpixel{false};
13 
14 int main() {
15  using namespace std;
16 
17  // Create pipeline
18  dai::Pipeline pipeline;
19 
20  // Define sources and outputs
21  auto monoLeft = pipeline.create<dai::node::MonoCamera>();
22  auto monoRight = pipeline.create<dai::node::MonoCamera>();
23  auto stereo = withDepth ? pipeline.create<dai::node::StereoDepth>() : nullptr;
24 
25  auto xoutLeft = pipeline.create<dai::node::XLinkOut>();
26  auto xoutRight = pipeline.create<dai::node::XLinkOut>();
27  auto xoutDisp = pipeline.create<dai::node::XLinkOut>();
28  auto xoutDepth = pipeline.create<dai::node::XLinkOut>();
29  auto xoutRectifL = pipeline.create<dai::node::XLinkOut>();
30  auto xoutRectifR = pipeline.create<dai::node::XLinkOut>();
31 
32  // XLinkOut
33  xoutLeft->setStreamName("left");
34  xoutRight->setStreamName("right");
35  if(withDepth) {
36  xoutDisp->setStreamName("disparity");
37  xoutDepth->setStreamName("depth");
38  xoutRectifL->setStreamName("rectified_left");
39  xoutRectifR->setStreamName("rectified_right");
40  }
41 
42  // Properties
44  monoLeft->setCamera("left");
46  monoRight->setCamera("right");
47 
48  if(withDepth) {
49  // StereoDepth
50  stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
51  stereo->setRectifyEdgeFillColor(0); // black, to better see the cutout
52  // stereo->setInputResolution(1280, 720);
53  stereo->initialConfig.setMedianFilter(dai::MedianFilter::KERNEL_5x5);
54  stereo->setLeftRightCheck(lrcheck);
55  stereo->setExtendedDisparity(extended);
56  stereo->setSubpixel(subpixel);
57 
58  // Linking
59  monoLeft->out.link(stereo->left);
60  monoRight->out.link(stereo->right);
61 
62  stereo->syncedLeft.link(xoutLeft->input);
63  stereo->syncedRight.link(xoutRight->input);
64  stereo->disparity.link(xoutDisp->input);
65 
66  if(outputRectified) {
67  stereo->rectifiedLeft.link(xoutRectifL->input);
68  stereo->rectifiedRight.link(xoutRectifR->input);
69  }
70 
71  if(outputDepth) {
72  stereo->depth.link(xoutDepth->input);
73  }
74 
75  } else {
76  // Link plugins CAM -> XLINK
77  monoLeft->out.link(xoutLeft->input);
78  monoRight->out.link(xoutRight->input);
79  }
80 
81  // Connect to device and start pipeline
82  dai::Device device(pipeline);
83 
84  auto leftQueue = device.getOutputQueue("left", 8, false);
85  auto rightQueue = device.getOutputQueue("right", 8, false);
86  auto dispQueue = withDepth ? device.getOutputQueue("disparity", 8, false) : nullptr;
87  auto depthQueue = withDepth ? device.getOutputQueue("depth", 8, false) : nullptr;
88  auto rectifLeftQueue = withDepth ? device.getOutputQueue("rectified_left", 8, false) : nullptr;
89  auto rectifRightQueue = withDepth ? device.getOutputQueue("rectified_right", 8, false) : nullptr;
90 
91  // Disparity range is used for normalization
92  float disparityMultiplier = withDepth ? 255 / stereo->initialConfig.getMaxDisparity() : 0;
93 
94  while(true) {
95  auto left = leftQueue->get<dai::ImgFrame>();
96  cv::imshow("left", left->getFrame());
97  auto right = rightQueue->get<dai::ImgFrame>();
98  cv::imshow("right", right->getFrame());
99 
100  if(withDepth) {
101  auto disparity = dispQueue->get<dai::ImgFrame>();
102  cv::Mat disp(disparity->getCvFrame());
103  disp.convertTo(disp, CV_8UC1, disparityMultiplier); // Extend disparity range
104  cv::imshow("disparity", disp);
105  cv::Mat disp_color;
106  cv::applyColorMap(disp, disp_color, cv::COLORMAP_JET);
107  cv::imshow("disparity_color", disp_color);
108 
109  if(outputDepth) {
110  auto depth = depthQueue->get<dai::ImgFrame>();
111  cv::imshow("depth", depth->getCvFrame());
112  }
113 
114  if(outputRectified) {
115  auto rectifL = rectifLeftQueue->get<dai::ImgFrame>();
116  cv::imshow("rectified_left", rectifL->getFrame());
117 
118  auto rectifR = rectifRightQueue->get<dai::ImgFrame>();
119  cv::imshow("rectified_right", rectifR->getFrame());
120  }
121  }
122 
123  int key = cv::waitKey(1);
124  if(key == 'q' || key == 'Q') {
125  return 0;
126  }
127  }
128  return 0;
129 }
dai::node::MonoCamera::out
Output out
Definition: MonoCamera.hpp:47
withDepth
static std::atomic< bool > withDepth
Definition: stereo_depth_video.cpp:6
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
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
subpixel
static std::atomic< bool > subpixel
Definition: stereo_depth_video.cpp:12
dai::Device::getOutputQueue
std::shared_ptr< DataOutputQueue > getOutputQueue(const std::string &name)
Definition: Device.cpp:86
dai::MonoCameraProperties::SensorResolution::THE_720_P
@ THE_720_P
main
int main()
Definition: stereo_depth_video.cpp:14
dai::node::XLinkOut::input
Input input
Definition: XLinkOut.hpp:27
depthai.hpp
dai::Pipeline::create
std::shared_ptr< N > create()
Definition: Pipeline.hpp:145
dai::node::MonoCamera::setResolution
void setResolution(Properties::SensorResolution resolution)
Set sensor resolution.
Definition: MonoCamera.cpp:82
dai::ImgFrame
Definition: ImgFrame.hpp:25
outputRectified
static std::atomic< bool > outputRectified
Definition: stereo_depth_video.cpp:9
extended
static std::atomic< bool > extended
Definition: stereo_depth_video.cpp:11
dai::node::StereoDepth::PresetMode::HIGH_DENSITY
@ HIGH_DENSITY
dai::Device
Definition: Device.hpp:21
std
Definition: Node.hpp:366
dai::Node::Output::link
void link(const Input &in)
Definition: Node.cpp:84
lrcheck
static std::atomic< bool > lrcheck
Definition: stereo_depth_video.cpp:10
dai::node::XLinkOut::setStreamName
void setStreamName(const std::string &name)
Definition: XLinkOut.cpp:13
dai::MedianFilter::KERNEL_5x5
@ KERNEL_5x5
outputDepth
static std::atomic< bool > outputDepth
Definition: stereo_depth_video.cpp:8


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