PointCloud.hpp
Go to the documentation of this file.
1 #pragma once
2 
4 
5 // standard
6 #include <fstream>
7 
8 // shared
10 
12 
13 namespace dai {
14 namespace node {
15 
19 class PointCloud : public NodeCRTP<Node, PointCloud, PointCloudProperties> {
20  public:
21  constexpr static const char* NAME = "PointCloud";
22 
23  protected:
25 
26  private:
27  std::shared_ptr<RawPointCloudConfig> rawConfig;
28 
29  public:
30  PointCloud(const std::shared_ptr<PipelineImpl>& par, int64_t nodeId);
31  PointCloud(const std::shared_ptr<PipelineImpl>& par, int64_t nodeId, std::unique_ptr<Properties> props);
32 
37 
42  Input inputConfig{*this, "inputConfig", Input::Type::SReceiver, false, 4, {{DatatypeEnum::PointCloudConfig, false}}};
43 
48  Input inputDepth{*this, "inputDepth", Input::Type::SReceiver, false, 4, true, {{DatatypeEnum::ImgFrame, false}}};
49 
53  Output outputPointCloud{*this, "outputPointCloud", Output::Type::MSender, {{DatatypeEnum::PointCloudData, false}}};
54 
59  Output passthroughDepth{*this, "passthroughDepth", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};
60 
65  void setNumFramesPool(int numFramesPool);
66 };
67 
68 } // namespace node
69 } // namespace dai
dai::PointCloudConfig
Definition: PointCloudConfig.hpp:14
dai::node::PointCloud::setNumFramesPool
void setNumFramesPool(int numFramesPool)
Definition: PointCloud.cpp:22
PointCloudProperties.hpp
dai::node::PointCloud::inputDepth
Input inputDepth
Definition: PointCloud.hpp:48
dai::node::PointCloud::initialConfig
PointCloudConfig initialConfig
Definition: PointCloud.hpp:36
dai::DatatypeEnum::PointCloudConfig
@ PointCloudConfig
dai::Node::Output
Definition: Node.hpp:67
dai::NodeCRTP
Definition: Node.hpp:342
dai::DatatypeEnum::PointCloudData
@ PointCloudData
dai::node::PointCloud::getProperties
Properties & getProperties()
Definition: PointCloud.cpp:17
dai::node::PointCloud::outputPointCloud
Output outputPointCloud
Definition: PointCloud.hpp:53
dai::Properties
Base Properties structure.
Definition: Properties.hpp:8
PointCloudConfig.hpp
dai::node::PointCloud::passthroughDepth
Output passthroughDepth
Definition: PointCloud.hpp:59
dai::node::PointCloud
PointCloud node. Computes point cloud from depth frames.
Definition: PointCloud.hpp:19
dai::node::PointCloud::inputConfig
Input inputConfig
Definition: PointCloud.hpp:42
dai::DatatypeEnum::ImgFrame
@ ImgFrame
dai
Definition: CameraExposureOffset.hpp:6
Node.hpp
dai::node::PointCloud::NAME
constexpr static const char * NAME
Definition: PointCloud.hpp:21
dai::node::PointCloud::PointCloud
PointCloud(const std::shared_ptr< PipelineImpl > &par, int64_t nodeId)
Definition: PointCloud.cpp:8
dai::node::PointCloud::rawConfig
std::shared_ptr< RawPointCloudConfig > rawConfig
Definition: PointCloud.hpp:27


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