# 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:

#### Python

```python
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...
```

#### C++

```cpp
#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

#### Python

### depthai.PointCloudConfig(depthai.Buffer)

Kind: Class

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

#### __init__()

Kind: Method

#### get(self) -> RawPointCloudConfig: RawPointCloudConfig

Kind: Method

Retrieve configuration data for SpatialLocationCalculator.

Returns:
config for SpatialLocationCalculator

#### getSparse(self) -> bool: bool

Kind: Method

Retrieve sparse point cloud calculation status.

Returns:
true if sparse point cloud calculation is enabled, false otherwise

#### getTransformationMatrix(self) -> typing.Annotated[list[typing.Annotated[list[float], FixedSize(4)]], FixedSize(4)]:
typing.Annotated[list[typing.Annotated[list[float], FixedSize(4)]], FixedSize(4)]

Kind: Method

Retrieve transformation matrix for point cloud calculation.

Returns:
4x4 transformation matrix

#### set(self, config: RawPointCloudConfig) -> PointCloudConfig: PointCloudConfig

Kind: Method

Set explicit configuration.

Parameter ``config``:
Explicit configuration

#### setSparse(self, arg0: bool) -> PointCloudConfig: PointCloudConfig

Kind: Method

Enable or disable sparse point cloud calculation.

Parameter ``enable``:

#### setTransformationMatrix()

Kind: Method

#### C++

### dai::PointCloudConfig

Kind: class

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

#### PointCloudConfig()

Kind: function

Construct PointCloudConfig message.

#### PointCloudConfig(std::shared_ptr< RawPointCloudConfig > ptr)

Kind: function

#### ~PointCloudConfig()

Kind: function

#### PointCloudConfig & set(dai::RawPointCloudConfig config)

Kind: function

Set explicit configuration. parameters: config: Explicit configuration

#### dai::RawPointCloudConfig get()

Kind: function

Retrieve configuration data for SpatialLocationCalculator. return: config for SpatialLocationCalculator

#### bool getSparse()

Kind: function

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

Kind: function

Retrieve transformation matrix for point cloud calculation. return: 4x4 transformation matrix

#### PointCloudConfig & setSparse(bool enable)

Kind: function

Enable or disable sparse point cloud calculation. parameters: enable:

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

Kind: function

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)

Kind: function

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

### Need assistance?

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