visualize_pointcloud.cpp
Go to the documentation of this file.
1 #include <iostream>
2 #include <opencv2/opencv.hpp>
3 
4 #include "depthai/depthai.hpp"
5 
6 int main() {
7  auto pipeline = dai::Pipeline();
8  auto monoLeft = pipeline.create<dai::node::MonoCamera>();
9  auto monoRight = pipeline.create<dai::node::MonoCamera>();
10  auto depth = pipeline.create<dai::node::StereoDepth>();
11  auto pointcloud = pipeline.create<dai::node::PointCloud>();
12  auto xout = pipeline.create<dai::node::XLinkOut>();
13  auto xoutDepth = pipeline.create<dai::node::XLinkOut>();
14 
16  monoLeft->setCamera("left");
18  monoRight->setCamera("right");
19 
20  // Create a node that will produce the depth map (using disparity output as
21  // it's easier to visualize depth this way)
22  depth->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
23  // Options: MEDIAN_OFF, KERNEL_3x3, KERNEL_5x5, KERNEL_7x7 (default)
24  depth->initialConfig.setMedianFilter(dai::MedianFilter::KERNEL_7x7);
25  depth->setLeftRightCheck(true);
26  depth->setExtendedDisparity(false);
27  depth->setSubpixel(true);
28 
29  xout->setStreamName("out");
30  xoutDepth->setStreamName("depth");
31 
32  monoLeft->out.link(depth->left);
33  monoRight->out.link(depth->right);
34  depth->depth.link(pointcloud->inputDepth);
35  depth->disparity.link(xoutDepth->input);
36  pointcloud->outputPointCloud.link(xout->input);
37  pointcloud->initialConfig.setSparse(true);
38 
39  auto viewer = std::make_unique<pcl::visualization::PCLVisualizer>("Cloud Viewer");
40  bool first = true;
41 
42  dai::Device device(pipeline);
43 
44  auto q = device.getOutputQueue("out", 8, false);
45  auto qDepth = device.getOutputQueue("depth", 8, false);
46  long counter = 0;
47  while(true) {
48  std::cout << "Waiting for data" << std::endl;
49  auto depthImg = qDepth->get<dai::ImgFrame>();
50  auto pclMsg = q->get<dai::PointCloudData>();
51  std::cout << "Got data" << std::endl;
52  if(!pclMsg) {
53  std::cout << "No data" << std::endl;
54  continue;
55  }
56 
57  auto frame = depthImg->getCvFrame();
58  frame.convertTo(frame, CV_8UC1, 255 / depth->initialConfig.getMaxDisparity());
59  cv::imshow("depth", frame);
60  cv::waitKey(1);
61 
62  if(pclMsg->getPoints().empty()) {
63  std::cout << "Empty point cloud" << std::endl;
64  continue;
65  }
66  std::cout << "Number of points: " << pclMsg->getPoints().size() << std::endl;
67  std::cout << "Min x: " << pclMsg->getMinX() << std::endl;
68  std::cout << "Min y: " << pclMsg->getMinY() << std::endl;
69  std::cout << "Min z: " << pclMsg->getMinZ() << std::endl;
70  std::cout << "Max x: " << pclMsg->getMaxX() << std::endl;
71  std::cout << "Max y: " << pclMsg->getMaxY() << std::endl;
72  std::cout << "Max z: " << pclMsg->getMaxZ() << std::endl;
73 
74  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = pclMsg->getPclData();
75  if(first) {
76  viewer->addPointCloud<pcl::PointXYZ>(cloud, "cloud");
77  first = false;
78  } else {
79  viewer->updatePointCloud(cloud, "cloud");
80  }
81 
82  viewer->spinOnce(10);
83 
84  if(viewer->wasStopped()) {
85  break;
86  }
87  }
88 
89  return 0;
90 }
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::initialConfig
StereoDepthConfig initialConfig
Definition: StereoDepth.hpp:52
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
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
dai::node::XLinkOut::input
Input input
Definition: XLinkOut.hpp:27
depthai.hpp
main
int main()
Definition: visualize_pointcloud.cpp:6
dai::PointCloudData
Definition: PointCloudData.hpp:22
dai::node::MonoCamera::setResolution
void setResolution(Properties::SensorResolution resolution)
Set sensor resolution.
Definition: MonoCamera.cpp:82
dai::ImgFrame
Definition: ImgFrame.hpp:25
dai::node::StereoDepth::PresetMode::HIGH_DENSITY
@ HIGH_DENSITY
dai::Device
Definition: Device.hpp:21
dai::node::PointCloud
PointCloud node. Computes point cloud from depth frames.
Definition: PointCloud.hpp:19
dai::MedianFilter::KERNEL_7x7
@ KERNEL_7x7
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