# PointCloud - TODO port to v3

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-v3/depthai/examples/pointcloud_visualization.md)
 * [PointCloud Control](https://docs.luxonis.com/software-v3/depthai/examples/pointcloud_control.md)

## Reference

#### Python

### dai::node::PointCloud

Kind: class

PointCloud node. Computes point cloud from depth frames.

#### dai::node::PointCloud::Impl

Kind: class

##### LengthUnit targetLengthUnit

Kind: variable

##### Impl()

Kind: function

##### void setLogger(std::shared_ptr<::spdlog::logger > log)

Kind: function

##### void computePointCloudDense(const uint8_t * depthData, std::vector< Point3f > & points)

Kind: function

##### void computePointCloudDenseColored(const uint8_t * depthData, const uint8_t * colorData, std::vector< Point3fRGBA > &
points)

Kind: function

##### void applyTransformation(std::vector< PointT > & points)

Kind: function

##### std::vector< PointT > filterValidPoints(const std::vector< PointT > & densePoints)

Kind: function

##### void setLengthUnit(dai::LengthUnit lengthUnit)

Kind: function

##### void useCPU()

Kind: function

##### void useCPUMT(uint32_t numThreads)

Kind: function

##### void useGPU(uint32_t device)

Kind: function

##### void setIntrinsics(float fx, float fy, float cx, float cy, unsigned int width, unsigned int height)

Kind: function

##### void setExtrinsics(const std::vector< std::vector< float >> & transformMatrix)

Kind: function

##### void clearExtrinsics()

Kind: function

#### std::shared_ptr< 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.

#### Subnode < node::Sync > sync

Kind: variable

Sync subnode for synchronized depth + color input. When only depth is connected, Sync passes through single-item MessageGroups.
When both depth and color are connected, Sync pairs them by timestamp.

#### InputMap & syncInputs

Kind: variable

#### Input & inputDepth

Kind: variable

Input message with depth data used to create the point cloud. Routed through the internal Sync subnode.

#### 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()

Kind: function

#### ~PointCloud()

Kind: function

#### Input & getColorInput()

Kind: function

Get the optional color input for colorized point clouds. Lazily creates the Sync entry so that depth-only mode works without Sync
waiting for a color frame that never arrives. Link an aligned color image (RGB888i, same dimensions as depth) to this input to
enable colored point cloud output.

#### void setNumFramesPool(int numFramesPool)

Kind: function

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

#### void setRunOnHost(bool runOnHost)

Kind: function

Specify whether to run on host or device By default, the node will run on host.

#### void useCPU()

Kind: function

Use single-threaded CPU for processing

#### void useCPUMT(uint32_t numThreads)

Kind: function

Use multi-threaded CPU for processing

#### void useGPU(uint32_t device)

Kind: function

Use GPU for point cloud computation parameters: device: GPU device index (default 0)

#### void setTargetCoordinateSystem(CameraBoardSocket targetCamera, bool useSpecTranslation)

Kind: function

Set target coordinate system to transform point cloud parameters: targetCamera: Target camera socket; useSpecTranslation: Use spec
translation instead of calibration (default: false)

#### void setTargetCoordinateSystem(HousingCoordinateSystem housingCS, bool useSpecTranslation)

Kind: function

Set target coordinate system to housing coordinate system Point cloud will be transformed to this housing coordinate system
parameters: housingCS: Target housing coordinate system; useSpecTranslation: Whether to use spec translation (default: true)

#### bool runOnHost()

Kind: function

Returns true or false whether the node should be run on host or not.

#### void buildInternal()

Kind: function

Function called from within the

#### C++

### dai::node::PointCloud

Kind: class

PointCloud node. Computes point cloud from depth frames.

#### dai::node::PointCloud::Impl

Kind: class

##### LengthUnit targetLengthUnit

Kind: variable

##### Impl()

Kind: function

##### void setLogger(std::shared_ptr<::spdlog::logger > log)

Kind: function

##### void computePointCloudDense(const uint8_t * depthData, std::vector< Point3f > & points)

Kind: function

##### void computePointCloudDenseColored(const uint8_t * depthData, const uint8_t * colorData, std::vector< Point3fRGBA > &
points)

Kind: function

##### void applyTransformation(std::vector< PointT > & points)

Kind: function

##### std::vector< PointT > filterValidPoints(const std::vector< PointT > & densePoints)

Kind: function

##### void setLengthUnit(dai::LengthUnit lengthUnit)

Kind: function

##### void useCPU()

Kind: function

##### void useCPUMT(uint32_t numThreads)

Kind: function

##### void useGPU(uint32_t device)

Kind: function

##### void setIntrinsics(float fx, float fy, float cx, float cy, unsigned int width, unsigned int height)

Kind: function

##### void setExtrinsics(const std::vector< std::vector< float >> & transformMatrix)

Kind: function

##### void clearExtrinsics()

Kind: function

#### std::shared_ptr< 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.

#### Subnode < node::Sync > sync

Kind: variable

Sync subnode for synchronized depth + color input. When only depth is connected, Sync passes through single-item MessageGroups.
When both depth and color are connected, Sync pairs them by timestamp.

#### InputMap & syncInputs

Kind: variable

#### Input & inputDepth

Kind: variable

Input message with depth data used to create the point cloud. Routed through the internal Sync subnode.

#### 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()

Kind: function

#### ~PointCloud()

Kind: function

#### Input & getColorInput()

Kind: function

Get the optional color input for colorized point clouds. Lazily creates the Sync entry so that depth-only mode works without Sync
waiting for a color frame that never arrives. Link an aligned color image (RGB888i, same dimensions as depth) to this input to
enable colored point cloud output.

#### void setNumFramesPool(int numFramesPool)

Kind: function

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

#### void setRunOnHost(bool runOnHost)

Kind: function

Specify whether to run on host or device By default, the node will run on host.

#### void useCPU()

Kind: function

Use single-threaded CPU for processing

#### void useCPUMT(uint32_t numThreads)

Kind: function

Use multi-threaded CPU for processing

#### void useGPU(uint32_t device)

Kind: function

Use GPU for point cloud computation parameters: device: GPU device index (default 0)

#### void setTargetCoordinateSystem(CameraBoardSocket targetCamera, bool useSpecTranslation)

Kind: function

Set target coordinate system to transform point cloud parameters: targetCamera: Target camera socket; useSpecTranslation: Use spec
translation instead of calibration (default: false)

#### void setTargetCoordinateSystem(HousingCoordinateSystem housingCS, bool useSpecTranslation)

Kind: function

Set target coordinate system to housing coordinate system Point cloud will be transformed to this housing coordinate system
parameters: housingCS: Target housing coordinate system; useSpecTranslation: Whether to use spec translation (default: true)

#### bool runOnHost()

Kind: function

Returns true or false whether the node should be run on host or not.

#### void buildInternal()

Kind: function

Function called from within the

### Need assistance?

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