PointCloudConfig

PointCloudConfig is a configuration class used to adjust settings for point cloud generation within the DepthAI ecosystem. It allows users to configure properties such as sparsity and transformation matrices, which are crucial for tailoring the point cloud data to specific application requirements.

Configuration Options

  • Sparsity: Determines whether the generated point cloud should be sparse. Sparse point clouds may omit points based on certain criteria, such as depth value thresholds, to reduce data volume and processing requirements.

  • Transformation Matrix: Applies a transformation matrix to the point cloud data, enabling rotations, translations, and scaling to align the point cloud with a world or application-specific coordinate system.

Usage

Configuring PointCloudConfig allows for precise control over the generation of point cloud data. Here’s an example of how to configure and apply PointCloudConfig in a DepthAI application:

import depthai as dai

# Create pipeline
pipeline = dai.Pipeline()

# Create PointCloud node
pointCloud = pipeline.create(dai.node.PointCloud)

pointCloud.initialConfig.setSparse(True) # Enable sparse point cloud generation

# Define a transformation matrix
transformationMatrix = [
    [1.0, 0.0, 0.0, 0.0],
    [0.0, 1.0, 0.0, 0.0],
    [0.0, 0.0, 1.0, 0.0],
    [0.0, 0.0, 0.0, 1.0]
]
pointCloud.initialConfig.setTransformationMatrix(transformationMatrix) # Apply transformation matrix

# Further pipeline setup and execution...
#include "depthai/depthai.hpp"

int main() {
    // Create pipeline
    dai::Pipeline pipeline;

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

    pointCloud->initialConfig.setSparse(true); // Enable sparse point cloud generation

    // Define a transformation matrix
    std::vector<std::vector<float>> transformationMatrix = {
        {1.0, 0.0, 0.0, 0.0},
        {0.0, 1.0, 0.0, 0.0},
        {0.0, 0.0, 1.0, 0.0},
        {0.0, 0.0, 0.0, 1.0}
    };
    pointCloud->initialConfig.setTransformationMatrix(transformationMatrix); // Apply transformation matrix

    // Further pipeline setup and execution...

    return 0;
}

This example demonstrates initializing PointCloudConfig, setting it to generate sparse point clouds, and applying a transformation matrix. This configuration is then applied to a PointCloud node within the DepthAI pipeline.

Examples of Functionality

  • 3D Object Localization: Adjusting the transformation matrix to align point clouds with a known coordinate system for precise object placement.

  • Scene Optimization: Utilizing sparse point clouds for efficient processing in large-scale or complex scenes.

  • Data Alignment: Applying transformation matrices for seamless integration of point cloud data with other sensor data or pre-existing 3D models.

Reference

class depthai.PointCloudConfig

PointCloudConfig message. Carries ROI (region of interest) and threshold for depth calculation

get(self: depthai.PointCloudConfig)depthai.RawPointCloudConfig

Retrieve configuration data for SpatialLocationCalculator.

Returns

config for SpatialLocationCalculator

getData(self: object) → numpy.ndarray[numpy.uint8]

Get non-owning reference to internal buffer

Returns

Reference to internal buffer

getRaw(self: depthai.ADatatype)depthai.RawBuffer
getSequenceNum(self: depthai.Buffer)int

Retrieves sequence number

getSparse(self: depthai.PointCloudConfig)bool

Retrieve sparse point cloud calculation status.

Returns

true if sparse point cloud calculation is enabled, false otherwise

getTimestamp(self: depthai.Buffer)datetime.timedelta

Retrieves timestamp related to dai::Clock::now()

getTimestampDevice(self: depthai.Buffer)datetime.timedelta

Retrieves timestamp directly captured from device’s monotonic clock, not synchronized to host time. Used mostly for debugging

getTransformationMatrix(self: depthai.PointCloudConfig) → List[List[float[4]][4]]

Retrieve transformation matrix for point cloud calculation.

Returns

4x4 transformation matrix

set(self: depthai.PointCloudConfig, config: depthai.RawPointCloudConfig)depthai.PointCloudConfig

Set explicit configuration.

Parameter config:

Explicit configuration

setData(*args, **kwargs)

Overloaded function.

  1. setData(self: depthai.Buffer, arg0: List[int]) -> None

Parameter data:

Copies data to internal buffer

  1. setData(self: depthai.Buffer, arg0: numpy.ndarray[numpy.uint8]) -> None

Parameter data:

Copies data to internal buffer

setSequenceNum(self: depthai.Buffer, arg0: int)depthai.Buffer

Retrieves sequence number

setSparse(self: depthai.PointCloudConfig, arg0: bool)depthai.PointCloudConfig

Enable or disable sparse point cloud calculation.

Parameter enable:

setTimestamp(self: depthai.Buffer, arg0: datetime.timedelta)depthai.Buffer

Sets timestamp related to dai::Clock::now()

setTimestampDevice(self: depthai.Buffer, arg0: datetime.timedelta)depthai.Buffer

Sets timestamp related to dai::Clock::now()

setTransformationMatrix(*args, **kwargs)

Overloaded function.

  1. setTransformationMatrix(self: depthai.PointCloudConfig, arg0: List[List[float[3]][3]]) -> depthai.PointCloudConfig

Set 4x4 transformation matrix for point cloud calculation. Default is an identity matrix.

Parameter transformationMatrix:

  1. setTransformationMatrix(self: depthai.PointCloudConfig, arg0: List[List[float[4]][4]]) -> depthai.PointCloudConfig

Set 4x4 transformation matrix for point cloud calculation. Default is an identity matrix.

Parameter transformationMatrix:

class dai::PointCloudConfig : public dai::Buffer

PointCloudConfig message. Carries ROI (region of interest) and threshold for depth calculation

Public Functions

PointCloudConfig()

Construct PointCloudConfig message.

PointCloudConfig(std::shared_ptr<RawPointCloudConfig> ptr)
~PointCloudConfig() = default
PointCloudConfig &set(dai::RawPointCloudConfig config)

Set explicit configuration.

Parameters
  • config: Explicit configuration

dai::RawPointCloudConfig get() const

Retrieve configuration data for SpatialLocationCalculator.

Return

config for SpatialLocationCalculator

bool getSparse() const

Retrieve sparse point cloud calculation status.

Return

true if sparse point cloud calculation is enabled, false otherwise

std::array<std::array<float, 4>, 4> getTransformationMatrix() const

Retrieve transformation matrix for point cloud calculation.

Return

4x4 transformation matrix

PointCloudConfig &setSparse(bool enable)

Enable or disable sparse point cloud calculation.

Parameters
  • enable:

PointCloudConfig &setTransformationMatrix(const std::array<std::array<float, 4>, 4> &transformationMatrix)

Set 4x4 transformation matrix for point cloud calculation. Default is an identity matrix.

Parameters
  • transformationMatrix:

PointCloudConfig &setTransformationMatrix(const std::array<std::array<float, 3>, 3> &transformationMatrix)

Set 3x3 transformation matrix for point cloud calculation. Default is an identity matrix.

Parameters
  • transformationMatrix:

Private Functions

std::shared_ptr<RawBuffer> serialize() const override

Private Members

RawPointCloudConfig &cfg

Got questions?

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