robokudo.annotators.pointcloud_cluster_extractor

Point cloud clustering and object detection.

This module provides annotators for:

  • Extracting object clusters from point clouds above detected planes

  • Generating ROIs and masks for detected clusters

  • Visualizing detected clusters with unique colors

The module uses DBSCAN clustering and oriented bounding boxes (OBB) for object detection.

Note

The clustering process requires a plane annotation in the CAS to function.

Attributes

Classes

PointCloudClusterExtractor

Annotator for object detection.

NaivePointCloudClusterExtractor

Annotator for object detection. Simply takes an input cloud and clusters it.

Functions

generate_roi_with_mask_from_points(image_height, ...)

Generate ROI and mask from projected point cloud points.

cluster_points(→ list)

Cluster points using DBSCAN algorithm.

Module Contents

robokudo.annotators.pointcloud_cluster_extractor.DILATION_KERNEL
robokudo.annotators.pointcloud_cluster_extractor.generate_roi_with_mask_from_points(image_height: int, image_width: int, pc_cam_intrinsics: open3d.camera.PinholeCameraIntrinsic, cloud: open3d.geometry.PointCloud, color2depth_ratio=(1, 1))

Generate ROI and mask from projected point cloud points.

Projects 3D points to image plane and creates:

  • ROI bounding the projected points

  • Binary mask of projected points

  • Dilated mask to account for point sparsity

Parameters:
  • image_height (int) – Height of the target image

  • image_width (int) – Width of the target image

  • pc_cam_intrinsics (o3d.camera.PinholeCameraIntrinsic) – Camera intrinsic parameters

  • cloud (o3d.geometry.PointCloud) – Point cloud to project

  • color2depth_ratio (tuple, optional) – Scale ratio between color and depth images, defaults to (1, 1)

Returns:

Tuple of (ROI with mask, full image mask)

Return type:

tuple(robokudo.types.cv.ImageROI, numpy.ndarray)

robokudo.annotators.pointcloud_cluster_extractor.cluster_points(input_cloud: open3d.geometry.PointCloud, eps: float, min_points: int, rk_logger: logging.Logger) list

Cluster points using DBSCAN algorithm.

Parameters:
  • input_cloud (o3d.geometry.PointCloud) – Point cloud to cluster

  • eps (float) – DBSCAN epsilon parameter (density threshold)

  • min_points (int) – Minimum points for a cluster

  • rk_logger (RcutilsLogger) – Logger instance for progress reporting

Returns:

List of point indices for each cluster

Return type:

list

Note

Points labeled as noise (label=-1) are ignored in the output.

class robokudo.annotators.pointcloud_cluster_extractor.PointCloudClusterExtractor(name='PointCloudClusterExtractor', descriptor=Descriptor())

Bases: robokudo.annotators.core.ThreadedAnnotator

Annotator for object detection.

The main idea is to look for the Plane annotation in the CAS extract the points that belong to the plane, constructs an oriented bounding box around it, pull it up to create volume above the plane and then extract all the inlier points. After that, a clustering process is executed and each cluster is annotated in the CAS.

Warning

Requires a Plane annotation in the CAS to function.

class Descriptor

Bases: robokudo.annotators.core.BaseAnnotator.Descriptor

Configuration descriptor for point cloud clustering.

class Parameters

Parameters for configuring cluster extraction.

Variables:
  • dbscan_min_cluster_count – Minimum points for DBSCAN cluster, defaults to 90

  • min_cluster_count – Minimum total points for valid cluster, defaults to 1000

  • min_on_plane_point_count – Minimum points above plane, defaults to 90

  • eps – DBSCAN epsilon parameter (density threshold), defaults to 0.04

dbscan_min_cluster_count = 90
min_cluster_count = 1000
min_on_plane_point_count = 90
eps = 0.04
parameters
points_and_indices_from_plane(plane_model: robokudo.types.annotation.Plane, cloud: open3d.geometry.PointCloud) tuple

Extract points above a detected plane.

Based on an input cloud and a plane model, extract all the points that are above that plane in the input cloud. Returns various data structures for further analysis and visualization.

Parameters:
Returns:

A tuple consisting of: plane_obb = The OBB around the points belonging to the plane_model in cloud on_plane_obb = The OBB put above plane_obb, with the same width and depth, but extended upwards on_plane_cloud = Points found in on_plane_obb on_plane_cloud_indices = Indices of Points found in on_plane_obb outlier_cloud = All points that do not belong to the plane/table itself.

Return type:

tuple

Raises:

Exception – If insufficient points found above plane

Note

The function ensures the plane normal points upward by rotating the OBB if necessary.

compute()

Process point cloud to detect and annotate object clusters.

The method:

  • Extracts points above detected plane

  • Clusters points using DBSCAN

  • Creates ObjectHypothesis annotations for each cluster

  • Generates ROIs and masks for visualization

  • Visualizes clusters with unique colors

Returns:

SUCCESS if clusters found, FAILURE if no clusters or errors

Return type:

py_trees.Status

Raises:

Exception – If no plane model in CAS or insufficient points

class robokudo.annotators.pointcloud_cluster_extractor.NaivePointCloudClusterExtractor(name='NaivePointCloudClusterExtractor', descriptor=Descriptor())

Bases: robokudo.annotators.core.ThreadedAnnotator

Annotator for object detection. Simply takes an input cloud and clusters it.

Note

Unlike PointCloudClusterExtractor, this does not require a plane model.

class Descriptor

Bases: robokudo.annotators.core.BaseAnnotator.Descriptor

Configuration descriptor for naive point cloud clustering.

class Parameters

Parameters for configuring cluster extraction.

Variables:
  • dbscan_min_cluster_count – Minimum points for DBSCAN cluster, defaults to 90

  • min_cluster_count – Minimum total points for valid cluster, defaults to 1000

  • min_on_plane_point_count – Minimum points above plane, defaults to 90

  • eps – DBSCAN epsilon parameter (density threshold), defaults to 0.04

dbscan_min_cluster_count = 90
min_cluster_count = 1000
min_on_plane_point_count = 90
eps = 0.04
parameters
compute()

Process point cloud to detect and annotate object clusters.

The method:

  • Clusters points directly using DBSCAN

  • Creates ObjectHypothesis annotations for each cluster

  • Generates ROIs and masks for visualization

  • Visualizes clusters with unique colors

Returns:

SUCCESS if clusters found, FAILURE if no clusters or errors

Return type:

py_trees.Status

Raises:

Exception – If insufficient points in clusters