depth_video_synced.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 int main() {
7  // Create pipeline
8  dai::Pipeline pipeline;
9 
10  // Define sources and outputs
11  auto monoLeft = pipeline.create<dai::node::MonoCamera>();
12  auto monoRight = pipeline.create<dai::node::MonoCamera>();
13  auto color = pipeline.create<dai::node::ColorCamera>();
14  auto stereo = pipeline.create<dai::node::StereoDepth>();
15  auto sync = pipeline.create<dai::node::Sync>();
16 
17  auto xoutGrp = pipeline.create<dai::node::XLinkOut>();
18 
19  // XLinkOut
20  xoutGrp->setStreamName("xout");
21 
22  // Properties
24  monoLeft->setCamera("left");
26  monoRight->setCamera("right");
27 
28  stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_ACCURACY);
29 
30  color->setCamera("color");
31 
32  sync->setSyncThreshold(std::chrono::milliseconds(100));
33 
34  // Linking
35  monoLeft->out.link(stereo->left);
36  monoRight->out.link(stereo->right);
37 
38  stereo->disparity.link(sync->inputs["disparity"]);
39  color->video.link(sync->inputs["video"]);
40 
41  sync->out.link(xoutGrp->input);
42 
43  // Connect to device and start pipeline
44  dai::Device device(pipeline);
45 
46  auto queue = device.getOutputQueue("xout", 10, true);
47 
48  float disparityMultiplier = 255 / stereo->initialConfig.getMaxDisparity();
49 
50  while(true) {
51  auto msgGrp = queue->get<dai::MessageGroup>();
52  for(auto& frm : *msgGrp) {
53  auto imgFrm = std::dynamic_pointer_cast<dai::ImgFrame>(frm.second);
54  cv::Mat img = imgFrm->getCvFrame();
55  if(frm.first == "disparity") {
56  img.convertTo(img, CV_8UC1, disparityMultiplier); // Extend disparity range
57  cv::applyColorMap(img, img, cv::COLORMAP_JET);
58  }
59  cv::imshow(frm.first, img);
60  }
61 
62  int key = cv::waitKey(1);
63  if(key == 'q' || key == 'Q') {
64  return 0;
65  }
66  }
67  return 0;
68 }
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
dai::MessageGroup
Definition: MessageGroup.hpp:16
dai::node::StereoDepth::PresetMode::HIGH_ACCURACY
@ HIGH_ACCURACY
dai::node::StereoDepth
StereoDepth node. Compute stereo disparity and depth from left-right image pair.
Definition: StereoDepth.hpp:15
dai::node::Sync
Definition: Sync.hpp:11
dai::node::MonoCamera
MonoCamera node. For use with grayscale sensors.
Definition: MonoCamera.hpp:17
dai::node::ColorCamera
ColorCamera node. For use with color sensors.
Definition: ColorCamera.hpp:16
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
dai::node::MonoCamera::setResolution
void setResolution(Properties::SensorResolution resolution)
Set sensor resolution.
Definition: MonoCamera.cpp:82
dai::Device
Definition: Device.hpp:21
dai::Node::Output::link
void link(const Input &in)
Definition: Node.cpp:84
main
int main()
Definition: depth_video_synced.cpp:6


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