robokudo.annotators.plane¶
Plane detection and visualization in point clouds.
This module provides an annotator for:
Detecting dominant planes using RANSAC
Creating plane model annotations
Visualizing detected planes and inliers
Supporting threaded execution
The plane detection uses:
RANSAC for robust model fitting
Distance threshold for inlier selection
Plane equation in ax + by + cz + d = 0 form
Note
Plane visualization includes both inlier points and a mesh model.
Classes¶
Plane detector and visualizer for point clouds. |
Module Contents¶
- class robokudo.annotators.plane.PlaneAnnotator(name='PlaneAnnotator', descriptor=Descriptor())¶
-
Bases:
robokudo.annotators.core.ThreadedAnnotatorPlane detector and visualizer for point clouds.
This annotator:
Detects largest plane using RANSAC
Creates plane model annotations
Visualizes plane inliers and model
Runs in a separate thread
Note
Uses Open3D’s plane segmentation with configurable parameters.
- class Descriptor¶
-
Bases:
robokudo.annotators.core.BaseAnnotator.DescriptorConfiguration descriptor for plane detection.
- class Parameters¶
-
Parameters for configuring plane detection.
- Variables:
-
visualize_plane_model – Show plane model mesh, defaults to True
- visualize_plane_model = True¶
- parameters¶
- compute()¶
-
Detect and annotate dominant plane in point cloud.
The method:
Loads point cloud from CAS
Detects plane using RANSAC: * Distance threshold: 0.02 * Sample size: 3 points * Iterations: 50
Creates plane annotation with: * Model parameters (a, b, c, d) * Inlier point indices
Visualizes results: * Inlier points in original cloud * Optional plane model mesh
- Returns:
-
SUCCESS after processing
- Return type:
-
py_trees.Status