mono_full_resolution_saver.cpp
Go to the documentation of this file.
1 #include <chrono>
2 #include <iostream>
3 
4 // Includes common necessary includes for development using depthai library
5 #include "depthai/depthai.hpp"
6 #include "utility.hpp"
7 
8 int main() {
9  using namespace std::chrono;
10  // Create pipeline
11  dai::Pipeline pipeline;
12 
13  // Define source and output
14  auto monoRight = pipeline.create<dai::node::MonoCamera>();
15  auto xoutRight = pipeline.create<dai::node::XLinkOut>();
16 
17  xoutRight->setStreamName("right");
18 
19  // Properties
20  monoRight->setCamera("right");
22 
23  // Linking
24  monoRight->out.link(xoutRight->input);
25 
26  // Connect to device and start pipeline
27  dai::Device device(pipeline);
28 
29  // Output queue will be used to get the grayscale frames from the output defined above
30  auto qRight = device.getOutputQueue("right", 4, false);
31 
32  std::string dirName = "mono_data";
33  createDirectory(dirName);
34 
35  while(true) {
36  auto inRight = qRight->get<dai::ImgFrame>();
37  // Data is originally represented as a flat 1D array, it needs to be converted into HxW form
38  // Frame is transformed and ready to be shown
39  cv::imshow("right", inRight->getCvFrame());
40 
41  uint64_t time = duration_cast<milliseconds>(system_clock::now().time_since_epoch()).count();
42  std::stringstream videoStr;
43  videoStr << dirName << "/" << time << ".png";
44  // After showing the frame, it's being stored inside a target directory as a PNG image
45  cv::imwrite(videoStr.str(), inRight->getCvFrame());
46 
47  int key = cv::waitKey(1);
48  if(key == 'q' || key == 'Q') {
49  return 0;
50  }
51  }
52  return 0;
53 }
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: mono_full_resolution_saver.cpp:8
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_720_P
@ THE_720_P
depthai.hpp
dai::Pipeline::create
std::shared_ptr< N > create()
Definition: Pipeline.hpp:145
dai::ImgFrame
Definition: ImgFrame.hpp:25
dai::Device
Definition: Device.hpp:21
createDirectory
int createDirectory(std::string directory)
Definition: utility.cpp:15
utility.hpp


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