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
-
get
(self: depthai.PointCloudConfig) → depthai.RawPointCloudConfig
-
getData
(self: object) → numpy.ndarray[numpy.uint8]
-
getRaw
(self: depthai.ADatatype) → depthai.RawBuffer
-
getSequenceNum
(self: depthai.Buffer) → int
-
getSparse
(self: depthai.PointCloudConfig) → bool
-
getTimestamp
(self: depthai.Buffer) → datetime.timedelta
-
getTimestampDevice
(self: depthai.Buffer) → datetime.timedelta
-
getTransformationMatrix
(self: depthai.PointCloudConfig) → Annotated[list[Annotated[list[float], FixedSize(4)]], FixedSize(4)]
-
set
(self: depthai.PointCloudConfig, config: depthai.RawPointCloudConfig) → depthai.PointCloudConfig
-
setData
(*args, **kwargs) Overloaded function.
setData(self: depthai.Buffer, arg0: list[int]) -> None
setData(self: depthai.Buffer, arg0: numpy.ndarray[numpy.uint8]) -> None
-
setSequenceNum
(self: depthai.Buffer, arg0: int) → depthai.Buffer
-
setSparse
(self: depthai.PointCloudConfig, arg0: bool) → depthai.PointCloudConfig
-
setTimestamp
(self: depthai.Buffer, arg0: datetime.timedelta) → depthai.Buffer
-
setTimestampDevice
(self: depthai.Buffer, arg0: datetime.timedelta) → depthai.Buffer
-
setTransformationMatrix
(*args, **kwargs) Overloaded function.
setTransformationMatrix(self: depthai.PointCloudConfig, arg0: Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]) -> depthai.PointCloudConfig
setTransformationMatrix(self: depthai.PointCloudConfig, arg0: Annotated[list[Annotated[list[float], FixedSize(4)]], FixedSize(4)]) -> depthai.PointCloudConfig
-
-
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
() = 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 Members
-
RawPointCloudConfig &
cfg
¶
-