robokudo.annotators.pointcloud_cluster_extractor ================================================ .. py:module:: robokudo.annotators.pointcloud_cluster_extractor Attributes ---------- .. autoapisummary:: robokudo.annotators.pointcloud_cluster_extractor.DILATION_KERNEL Classes ------- .. autoapisummary:: robokudo.annotators.pointcloud_cluster_extractor.PointCloudClusterExtractor robokudo.annotators.pointcloud_cluster_extractor.NaivePointCloudClusterExtractor Functions --------- .. autoapisummary:: robokudo.annotators.pointcloud_cluster_extractor.generate_roi_with_mask_from_points robokudo.annotators.pointcloud_cluster_extractor.cluster_points Module Contents --------------- .. py:data:: DILATION_KERNEL .. py:function:: 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)) -> (robokudo.types.cv.ImageROI, numpy.ndarray) .. py:function:: cluster_points(input_cloud: open3d.geometry.PointCloud, eps: float, min_points: int, rk_logger: rosgraph.roslogging.RospyLogger) -> list .. py:class:: PointCloudClusterExtractor(name='PointCloudClusterExtractor', descriptor=Descriptor()) Bases: :py:obj:`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. .. py:class:: Descriptor Bases: :py:obj:`robokudo.annotators.core.BaseAnnotator.Descriptor` .. py:class:: Parameters .. py:attribute:: dbscan_min_cluster_count :value: 90 .. py:attribute:: min_cluster_count :value: 1000 .. py:attribute:: min_on_plane_point_count :value: 90 .. py:attribute:: eps :value: 0.04 .. py:attribute:: parameters .. py:method:: points_and_indices_from_plane(plane_model: robokudo.types.annotation.Plane, cloud: open3d.geometry.PointCloud) -> tuple 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. :param plane_model: :param cloud: :return: 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. .. py:method:: compute() .. py:class:: NaivePointCloudClusterExtractor(name='NaivePointCloudClusterExtractor', descriptor=Descriptor()) Bases: :py:obj:`robokudo.annotators.core.ThreadedAnnotator` Annotator for object detection. Simply takes an input cloud and clusters it. .. py:class:: Descriptor Bases: :py:obj:`robokudo.annotators.core.BaseAnnotator.Descriptor` .. py:class:: Parameters .. py:attribute:: dbscan_min_cluster_count :value: 90 .. py:attribute:: min_cluster_count :value: 1000 .. py:attribute:: min_on_plane_point_count :value: 90 .. py:attribute:: eps :value: 0.04 .. py:attribute:: parameters .. py:method:: compute()