Segmentation is the algorithm for tabletop/shelf segmentation. More...
#include <segmentation.h>
Public Member Functions | |
bool | Segment (std::vector< SurfaceObjects > *surfaces) const |
Segments the scene. | |
Segmentation () | |
Default constructor. | |
void | set_cluster_distance (double cluster_distance) |
Sets the minimum distance between object clusters. | |
void | set_horizontal_tolerance_degrees (double degrees) |
Sets the tolerance for a surface to be considered horizontal. | |
void | set_indices (pcl::PointIndicesPtr indices) |
Sets the indices in the point cloud to use as input. | |
void | set_input_cloud (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud) |
Sets the input cloud to use. | |
void | set_margin_above_surface (double margin) |
Sets a margin above the surface to start segmenting objects from. | |
void | set_max_cluster_size (int max_cluster_size) |
Sets the minimum cluster size. | |
void | set_max_point_distance (double max_point_distance) |
Sets the maximum distance of inlier points considered to be part of a surface. | |
void | set_min_cluster_size (int min_cluster_size) |
Sets the minimum cluster size. | |
void | set_min_surface_exploration_iteration (int min_surface_exploration_iteration) |
Sets the minimum number of iterations required when exploring surfaces in the input point cloud. | |
void | set_min_surface_size (int min_surface_size) |
Sets the minimum number of points a surface has to have. | |
Private Attributes | |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr | cloud_ |
double | cluster_distance_ |
double | horizontal_tolerance_degrees_ |
pcl::PointIndicesPtr | indices_ |
double | margin_above_surface_ |
int | max_cluster_size_ |
double | max_point_distance_ |
int | min_cluster_size_ |
int | min_surface_exploration_iteration_ |
int | min_surface_size_ |
Segmentation is the algorithm for tabletop/shelf segmentation.
This algorithm takes in a tabletop/shelf scene and segments it into surfaces with some number of objects above each surface. The objects are segmented using a Euclidean clustering algorithm. For each surface, The algorithm fits oriented bounding boxes around the surface and the objects. For each object, the z direction points "up," and the x direction points toward the shorter side of the oriented bounding box.
The algorithm assumes that the input scene is provided such that the positive z direction points "up."
Example usage:
surface_perception::Segmentation seg; seg.set_input_cloud(pcl_cloud); seg.set_indices(point_indices); seg.set_horizontal_tolerance_degrees(10); seg.set_margin_above_surface(0.01); seg.set_cluster_distance(0.01); seg.set_min_cluster_size(10); seg.set_max_cluster_size(10000); seg.set_min_surface_size(10000); std::vector<SurfaceObjects> surface_objects; bool success = seg.Segment(&surface_objects);
Definition at line 42 of file segmentation.h.
Default constructor.
Definition at line 30 of file segmentation.cpp.
bool surface_perception::Segmentation::Segment | ( | std::vector< SurfaceObjects > * | surfaces | ) | const |
Segments the scene.
[out] | surfaces | The vector of SurfaceObjects to append to. This algorithm only supports tabletop segmentation at this time, so it will append one SurfaceObjects instance if successful. |
Definition at line 77 of file segmentation.cpp.
void surface_perception::Segmentation::set_cluster_distance | ( | double | cluster_distance | ) |
Sets the minimum distance between object clusters.
The algorithm clusters nearby points and considers each cluster an object. This parameter is the threshold used to determine if two points are part of the same object or if they are part of different objects.
[in] | cluster_distance | The cluster distance, in the same units as the point cloud (usually meters). |
Definition at line 57 of file segmentation.cpp.
void surface_perception::Segmentation::set_horizontal_tolerance_degrees | ( | double | degrees | ) |
Sets the tolerance for a surface to be considered horizontal.
[in] | degrees | The tolerance, in degrees, for a surface to be considered horizontal. |
Definition at line 51 of file segmentation.cpp.
void surface_perception::Segmentation::set_indices | ( | pcl::PointIndicesPtr | indices | ) |
Sets the indices in the point cloud to use as input.
Definition at line 47 of file segmentation.cpp.
void surface_perception::Segmentation::set_input_cloud | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr | cloud | ) |
Sets the input cloud to use.
The cloud should be provided such that the positive z direction points up.
Definition at line 42 of file segmentation.cpp.
void surface_perception::Segmentation::set_margin_above_surface | ( | double | margin | ) |
Sets a margin above the surface to start segmenting objects from.
The algorithm fits a plane to the surface. Some points above that plane will correspond to the surface, so the margin is used to ignore all points within a certain distance above the plane.
[in] | margin | The margin, in the same units as the point cloud (usually meters), above the fitted plane to consider as part of the surface. |
Definition at line 54 of file segmentation.cpp.
void surface_perception::Segmentation::set_max_cluster_size | ( | int | max_cluster_size | ) |
Sets the minimum cluster size.
The algorithm clusters nearby points and considers each cluster an object. This parameter is used to filter out large parts of the scene that are above the surface but are not objects (e.g., a back wall). This parameter is sensitive to the density of the input point cloud.
[in] | max_cluster_size | The maximum number of points that can be in a cluster for the cluster to be considered an object. |
Definition at line 63 of file segmentation.cpp.
void surface_perception::Segmentation::set_max_point_distance | ( | double | max_point_distance | ) |
Sets the maximum distance of inlier points considered to be part of a surface.
As the surface exploration algorithm explores surfaces in the given point cloud scene, the value of max_point_distance is used to compute the number of inlier points for a surface. The number of surface inliers is then used to determine the quality of the explored surfaces for the output.
[in] | max_point_distance | The maximum distance threshold of surface inlier points. |
Definition at line 73 of file segmentation.cpp.
void surface_perception::Segmentation::set_min_cluster_size | ( | int | min_cluster_size | ) |
Sets the minimum cluster size.
The algorithm clusters nearby points and considers each cluster an object. This parameter is used as a filter to ignore noise. This parameter is sensitive to the density of the input point cloud.
[in] | min_cluster_size | The number of points that must be in a cluster for that cluster to be considered an object. |
Definition at line 60 of file segmentation.cpp.
void surface_perception::Segmentation::set_min_surface_exploration_iteration | ( | int | min_surface_exploration_iteration | ) |
Sets the minimum number of iterations required when exploring surfaces in the input point cloud.
The surface exploration algorithm samples a height value for a horizontal at each iteration, and min_surface_exploration_iteration indicates the lower bound of number of iterations needed for the horizontal surface sampling process.
[in] | min_surface_exploration_iteration | The surface exploration algorithm needs to run at least the specified number of iteration during surface exploration. |
Definition at line 69 of file segmentation.cpp.
void surface_perception::Segmentation::set_min_surface_size | ( | int | min_surface_size | ) |
Sets the minimum number of points a surface has to have.
As the algorithm only considers surfaces with more than required number of points as valid surfaces, the lower bound of surface size is used in order to ignore invalid surfaces
[in] | min_surface_size | The minimum requirement on number of points in a surface. |
Definition at line 66 of file segmentation.cpp.
pcl::PointCloud<pcl::PointXYZRGB>::Ptr surface_perception::Segmentation::cloud_ [private] |
Definition at line 151 of file segmentation.h.
double surface_perception::Segmentation::cluster_distance_ [private] |
Definition at line 156 of file segmentation.h.
double surface_perception::Segmentation::horizontal_tolerance_degrees_ [private] |
Definition at line 154 of file segmentation.h.
pcl::PointIndicesPtr surface_perception::Segmentation::indices_ [private] |
Definition at line 152 of file segmentation.h.
double surface_perception::Segmentation::margin_above_surface_ [private] |
Definition at line 155 of file segmentation.h.
int surface_perception::Segmentation::max_cluster_size_ [private] |
Definition at line 159 of file segmentation.h.
double surface_perception::Segmentation::max_point_distance_ [private] |
Definition at line 157 of file segmentation.h.
int surface_perception::Segmentation::min_cluster_size_ [private] |
Definition at line 158 of file segmentation.h.
Definition at line 161 of file segmentation.h.
int surface_perception::Segmentation::min_surface_size_ [private] |
Definition at line 160 of file segmentation.h.