PointCloud

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

How to place it

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

Inputs and Outputs

               ┌─────────────────────┐
               │                     │
inputConfig    │     PointCloud      │
──────────────►│                     │        outputPointCloud
               │                     ├────────────────►
inputDepth     │                     │        passthroughDepth
──────────────►│---------------------├────────────────►
               └─────────────────────┘

Message types

Example visualization with Open3D

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

Reference

class depthai.node.PointCloud
class Id

Node identificator. Unique for every node on a single Pipeline

getAssetManager(*args, **kwargs)

Overloaded function.

  1. getAssetManager(self: depthai.Node) -> depthai.AssetManager

  2. getAssetManager(self: depthai.Node) -> depthai.AssetManager

getInputRefs(*args, **kwargs)

Overloaded function.

  1. getInputRefs(self: depthai.Node) -> list[depthai.Node.Input]

  2. getInputRefs(self: depthai.Node) -> list[depthai.Node.Input]

getInputs(self: depthai.Node)list[depthai.Node.Input]
getName(self: depthai.Node)str
getOutputRefs(*args, **kwargs)

Overloaded function.

  1. getOutputRefs(self: depthai.Node) -> list[depthai.Node.Output]

  2. getOutputRefs(self: depthai.Node) -> list[depthai.Node.Output]

getOutputs(self: depthai.Node)list[depthai.Node.Output]
getParentPipeline(*args, **kwargs)

Overloaded function.

  1. getParentPipeline(self: depthai.Node) -> depthai.Pipeline

  2. getParentPipeline(self: depthai.Node) -> depthai.Pipeline

setNumFramesPool(self: depthai.node.PointCloud, arg0: int)None
class dai::node::PointCloud : public dai::NodeCRTP<Node, PointCloud, PointCloudProperties>

PointCloud node. Computes point cloud from depth frames.

Public Functions

PointCloud(const std::shared_ptr<PipelineImpl> &par, int64_t nodeId)
PointCloud(const std::shared_ptr<PipelineImpl> &par, int64_t nodeId, std::unique_ptr<Properties> props)
void setNumFramesPool(int numFramesPool)

Specify number of frames in pool.

Parameters
  • numFramesPool: How many frames should the pool have

Public Members

PointCloudConfig initialConfig

Initial config to use when computing the point cloud.

Input inputConfig = {*this, "inputConfig", Input::Type::SReceiver, false, 4, {{DatatypeEnum::PointCloudConfig, false}}}

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

Input inputDepth = {*this, "inputDepth", Input::Type::SReceiver, false, 4, true, {{DatatypeEnum::ImgFrame, false}}}

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

Output outputPointCloud = {*this, "outputPointCloud", Output::Type::MSender, {{DatatypeEnum::PointCloudData, false}}}

Outputs PointCloudData message

Output passthroughDepth = {*this, "passthroughDepth", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

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

Public Static Attributes

static constexpr const char *NAME = "PointCloud"

Private Members

std::shared_ptr<RawPointCloudConfig> rawConfig

Got questions?

Head over to Discussion Forum for technical support or any other questions you might have.