# PointCloud

The PointCloud node enables on-device point cloud generation from depth map.

## How to place it

#### Python

```python
pipeline = dai.Pipeline()
pointCloud = pipeline.create(dai.node.PointCloud)
```

#### C++

```cpp
dai::Pipeline pipeline;
auto pointCloud = pipeline.create<dai::node::PointCloud>();
```

## Inputs and Outputs

## Example visualization with Open3D

#### Python

```python
import open3d as o3d
import numpy as np
import depthai as dai

pcd = o3d.geometry.PointCloud()
vis = o3d.visualization.VisualizerWithKeyCallback()
vis.create_window()

with dai.Device(pipeline) as device:
    coordinateFrame = o3d.geometry.TriangleMesh.create_coordinate_frame(size=1000, origin=[0,0,0])
    vis.add_geometry(coordinateFrame)
    
    while device.isPipelineRunning():
        inMessage = q.get()
        inColor = inMessage["rgb"]
        inPointCloud = inMessage["pcl"]
        cvColorFrame = inColor.getCvFrame()
      
        if inPointCloud:
            points = inPointCloud.getPoints().astype(np.float64)
            pcd.points = o3d.utility.Vector3dVector(points)
            colors = (cvRGBFrame.reshape(-1, 3) / 255.0).astype(np.float64)
            pcd.colors = o3d.utility.Vector3dVector(colors)
            vis.update_geometry(pcd)

        vis.poll_events()
        vis.update_renderer()

    vis.destroy_window()
```

#### C++

```cpp
#include <iostream>
#include <open3d/Open3D.h>
#include <depthai/depthai.hpp>

int main() {
    auto viewer = std::make_unique<pcl::visualization::PCLVisualizer>("Cloud Viewer");
    viewer->addPointCloud<pcl::PointXYZ>(cloud, "cloud");

    dai::Device device(pipeline);

    auto q = device.getOutputQueue("out", 8, false);
    auto qDepth = device.getOutputQueue("depth", 8, false);

    while(true) {
        std::cout << "Waiting for data" << std::endl;
        auto depthImg = qDepth->get<dai::ImgFrame>();
        auto pclMsg = q->get<dai::PointCloudData>();
        
        if(!pclMsg) {
            std::cout << "No data" << std::endl;
            continue;
        }

        auto frame = depthImg->getCvFrame();
        frame.convertTo(frame, CV_8UC1, 255 / depth->initialConfig.getMaxDisparity());

        if(pclMsg->getPoints().empty()) {
            std::cout << "Empty point cloud" << std::endl;
            continue;
        }

        pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = pclMsg->getPclData();
        viewer->updatePointCloud(cloud, "cloud");
        
        viewer->spinOnce(10);

        if(viewer->wasStopped()) {
            break;
        }
    }
}
```

## Examples using PointCloud

 * [PointCloud Visualization](https://docs.luxonis.com/software/depthai/examples/pointcloud_visualization.md)
 * [PointCloud Control](https://docs.luxonis.com/software/depthai/examples/pointcloud_control.md)

## Reference

#### Python

### depthai.node.PointCloud(depthai.Node)

Kind: Class

PointCloud node. Computes point cloud from depth frames.

#### setNumFramesPool(self, arg0: typing.SupportsInt)

Kind: Method

Specify number of frames in pool.

Parameter ``numFramesPool``:
How many frames should the pool have

#### initialConfig

Kind: Property

Initial config to use when computing the point cloud.

#### inputConfig

Kind: Property

Input PointCloudConfig message with ability to modify parameters in runtime.
Default queue is non-blocking with size 4.

#### inputDepth

Kind: Property

Input message with depth data used to create the point cloud. Default queue is
non-blocking with size 4.

#### outputPointCloud

Kind: Property

Outputs PointCloudData message

#### passthroughDepth

Kind: Property

Passthrough depth from which the point cloud was calculated. Suitable for when
input queue is set to non-blocking behavior.

#### C++

### dai::node::PointCloud

Kind: class

PointCloud node. Computes point cloud from depth frames.

#### PointCloudConfig initialConfig

Kind: variable

Initial config to use when computing the point cloud.

#### Input inputConfig

Kind: variable

Input PointCloudConfig message with ability to modify parameters in runtime. Default queue is non-blocking with size 4.

#### Input inputDepth

Kind: variable

Input message with depth data used to create the point cloud. Default queue is non-blocking with size 4.

#### Output outputPointCloud

Kind: variable

Outputs PointCloudData message

#### Output passthroughDepth

Kind: variable

Passthrough depth from which the point cloud was calculated. Suitable for when input queue is set to non-blocking behavior.

#### PointCloud(const std::shared_ptr< PipelineImpl > & par, int64_t nodeId)

Kind: function

#### PointCloud(const std::shared_ptr< PipelineImpl > & par, int64_t nodeId, std::unique_ptr< Properties > props)

Kind: function

#### void setNumFramesPool(int numFramesPool)

Kind: function

Specify number of frames in pool. parameters: numFramesPool: How many frames should the pool have

### Need assistance?

Head over to [Discussion Forum](https://discuss.luxonis.com/) for technical support or any other questions you might have.
