calibration_load.cpp
Go to the documentation of this file.
1 #include <cstdio>
2 #include <iostream>
3 #include <string>
4 
5 // Includes common necessary includes for development using depthai library
8 #include "depthai/depthai.hpp"
9 
10 int main(int argc, char** argv) {
11  std::string calibJsonFile(CALIB_PATH);
12  if(argc > 1) {
13  calibJsonFile = std::string(argv[1]);
14  }
15  dai::CalibrationHandler calibData(calibJsonFile);
16 
17  // Create pipeline
18  dai::Pipeline pipeline;
19  pipeline.setCalibrationData(calibData);
20 
21  // Define sources and output
22  auto monoLeft = pipeline.create<dai::node::MonoCamera>();
23  auto monoRight = pipeline.create<dai::node::MonoCamera>();
24  auto stereo = pipeline.create<dai::node::StereoDepth>();
25  auto xoutDepth = pipeline.create<dai::node::XLinkOut>();
26  xoutDepth->setStreamName("depth");
27 
28  // MonoCamera
30  monoLeft->setCamera("left");
31  // monoLeft->setFps(5.0);
33  monoRight->setCamera("right");
34  // monoRight->setFps(5.0);
35 
36  // Linking
37  monoLeft->out.link(stereo->left);
38  monoRight->out.link(stereo->right);
39  stereo->depth.link(xoutDepth->input);
40 
41  // Connect to device and start pipeline
42  dai::Device device(pipeline);
43 
44  auto depthQueue = device.getOutputQueue("depth", 4, false);
45 
46  while(true) {
47  // blocking call, will wait until a new data has arrived
48  auto inDepth = depthQueue->get<dai::ImgFrame>();
49  cv::Mat frame = cv::Mat(inDepth->getHeight(), inDepth->getWidth(), CV_16UC1, inDepth->getData().data());
50 
51  // frame is ready to be shown
52  cv::imshow("depth", frame);
53 
54  int key = cv::waitKey(1);
55  if(key == 'q') {
56  return 0;
57  }
58  }
59  return 0;
60 }
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::StereoDepth
StereoDepth node. Compute stereo disparity and depth from left-right image pair.
Definition: StereoDepth.hpp:15
main
int main(int argc, char **argv)
Definition: calibration_load.cpp:10
CameraBoardSocket.hpp
dai::node::MonoCamera
MonoCamera node. For use with grayscale sensors.
Definition: MonoCamera.hpp:17
dai::Pipeline::setCalibrationData
void setCalibrationData(CalibrationHandler calibrationDataHandler)
Definition: Pipeline.hpp:233
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::node::MonoCamera::setResolution
void setResolution(Properties::SensorResolution resolution)
Set sensor resolution.
Definition: MonoCamera.cpp:82
EepromData.hpp
dai::ImgFrame
Definition: ImgFrame.hpp:25
dai::CalibrationHandler
Definition: CalibrationHandler.hpp:24
dai::Device
Definition: Device.hpp:21
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:18