mono_preview.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 xoutLeft = pipeline.create<dai::node::XLinkOut>();
14  auto xoutRight = pipeline.create<dai::node::XLinkOut>();
15 
16  xoutLeft->setStreamName("left");
17  xoutRight->setStreamName("right");
18 
19  // Properties
20  monoLeft->setCamera("left");
22  monoRight->setCamera("right");
24 
25  // Linking
26  monoRight->out.link(xoutRight->input);
27  monoLeft->out.link(xoutLeft->input);
28 
29  // Connect to device and start pipeline
30  dai::Device device(pipeline);
31 
32  // Output queues will be used to get the grayscale frames from the outputs defined above
33  auto qLeft = device.getOutputQueue("left", 4, false);
34  auto qRight = device.getOutputQueue("right", 4, false);
35 
36  while(true) {
37  // Instead of get (blocking), we use tryGet (non-blocking) which will return the available data or None otherwise
38  auto inLeft = qLeft->tryGet<dai::ImgFrame>();
39  auto inRight = qRight->tryGet<dai::ImgFrame>();
40 
41  if(inLeft) {
42  cv::imshow("left", inLeft->getCvFrame());
43  }
44 
45  if(inRight) {
46  cv::imshow("right", inRight->getCvFrame());
47  }
48 
49  int key = cv::waitKey(1);
50  if(key == 'q' || key == 'Q') {
51  return 0;
52  }
53  }
54  return 0;
55 }
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::node::MonoCamera
MonoCamera node. For use with grayscale sensors.
Definition: MonoCamera.hpp:17
main
int main()
Definition: mono_preview.cpp:6
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
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::getCvFrame
void getCvFrame(T...)
Definition: ImgFrame.hpp:222
dai::ImgFrame
Definition: ImgFrame.hpp:25
dai::Device
Definition: Device.hpp:21
dai::Node::Output::link
void link(const Input &in)
Definition: Node.cpp:84
dai::node::XLinkOut::setStreamName
void setStreamName(const std::string &name)
Definition: XLinkOut.cpp:13


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