pointcloud_test.cpp
Go to the documentation of this file.
1 #include <catch2/catch_all.hpp>
2 #include <catch2/catch_test_macros.hpp>
3 #include <depthai/depthai.hpp>
4 
7 
8 dai::Pipeline getPipeline(bool sparse) {
9  dai::Pipeline pipeline;
10  auto monoLeft = pipeline.create<dai::node::MonoCamera>();
11  auto monoRight = pipeline.create<dai::node::MonoCamera>();
12  auto stereo = pipeline.create<dai::node::StereoDepth>();
13  auto pointcloud = pipeline.create<dai::node::PointCloud>();
14  auto xout = pipeline.create<dai::node::XLinkOut>();
15 
16  monoLeft->setCamera("left");
17  monoRight->setCamera("right");
18 
21 
22  stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
23  stereo->setOutputSize(1280, 720);
24 
25  xout->setStreamName("out");
26 
27  pointcloud->initialConfig.setSparse(sparse);
28 
29  monoLeft->out.link(stereo->left);
30  monoRight->out.link(stereo->right);
31  stereo->depth.link(pointcloud->inputDepth);
32  pointcloud->outputPointCloud.link(xout->input);
33 
34  return pipeline;
35 }
36 
37 TEST_CASE("dense pointcloud") {
38  dai::Device device(getPipeline(false));
39 
40  auto outQ = device.getOutputQueue("out");
41  for(int i = 0; i < 10; ++i) {
42  auto pcl = outQ->get<dai::PointCloudData>();
43  REQUIRE(pcl != nullptr);
44  REQUIRE(pcl->getWidth() == 1280);
45  REQUIRE(pcl->getHeight() == 720);
46  REQUIRE(pcl->getPoints().size() == 1280UL * 720UL);
47  REQUIRE(pcl->getMinX() < 0.0f);
48  REQUIRE(pcl->getMaxX() > 0.0f);
49  REQUIRE(pcl->getMinY() < 0.0f);
50  REQUIRE(pcl->getMaxY() > 0.0f);
51  }
52 }
53 
54 TEST_CASE("sparse pointcloud") {
55  dai::Device device(getPipeline(true));
56 
57  auto outQ = device.getOutputQueue("out");
58  for(int i = 0; i < 10; ++i) {
59  auto pcl = outQ->get<dai::PointCloudData>();
60  REQUIRE(pcl != nullptr);
61  REQUIRE(pcl->getWidth() == 1280);
62  REQUIRE(pcl->getHeight() == 720);
63  REQUIRE(pcl->getPoints().size() < 1280UL * 720UL);
64  REQUIRE(pcl->getMinX() < 0.0f);
65  REQUIRE(pcl->getMaxX() > 0.0f);
66  REQUIRE(pcl->getMinY() < 0.0f);
67  REQUIRE(pcl->getMaxY() > 0.0f);
68  REQUIRE(pcl->getMinZ() > 0.0f);
69  }
70 }
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
TEST_CASE
TEST_CASE("dense pointcloud")
Definition: pointcloud_test.cpp:37
dai::MonoCameraProperties::SensorResolution::THE_720_P
@ THE_720_P
depthai.hpp
dai::Pipeline::create
std::shared_ptr< N > create()
Definition: Pipeline.hpp:145
dai::PointCloudData
Definition: PointCloudData.hpp:22
dai::node::MonoCamera::setResolution
void setResolution(Properties::SensorResolution resolution)
Set sensor resolution.
Definition: MonoCamera.cpp:82
getPipeline
dai::Pipeline getPipeline(bool sparse)
Definition: pointcloud_test.cpp:8
StereoDepthProperties.hpp
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::Node::Output::link
void link(const Input &in)
Definition: Node.cpp:84
PointCloudData.hpp


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