Only released in EOL distros:
Package Summary
Simple library for segmentation of tabletop and shelf surfaces
- Maintainer status: developed
- Maintainer: Justin Huang <jstn AT cs.washington DOT edu>
- Author: Yu-Tang Peng <pengy25 AT cs.washington DOT edu>
- License: BSD
- Source: git https://github.com/jstnhuang/surface_perception.git (branch: indigo-devel)
Contents
Use GitHub to report bugs or submit feature requests. [View active issues]
Overview
surface_perception is a simple tabletop/shelf perception pipeline.
surface_perception::Segmentation is the main API. It takes in a point cloud, where the positive "z" direction points up. It also assumes that the point cloud has been cropped down to a tabletop/shelf scene.
Example:
1 surface_perception::Segmentation seg;
2 seg.set_input_cloud(pcl_cloud);
3
4 // (Optional) Set the particular indices to be used in the input point cloud,
5 // for the segmentation operation. If the indices is not set, the entire
6 // input cloud will be used.
7 seg.set_indices(point_indices);
8
9 // (Optional, default 10) Set the maximum difference between the normal
10 // vector of surfaces and the z-axis.
11 seg.set_horizontal_tolerance_degrees(10);
12
13 // (Optional, default 0.005) Set the maximum distance between the surface
14 // inliers and the plane that represents the surface.
15 seg.set_margin_above_surface(0.01);
16
17 // (Optional, default 0.01) Set the required distance between each cluster
18 // corresponding to each object, during the object extraction.
19 seg.set_cluster_distance(0.01);
20
21 // (Optional, default 10) Set the minimum size of object clusters.
22 seg.set_min_cluster_size(10);
23
24 // (Optional, default 10000) Set the maximum size of object clusters.
25 seg.set_max_cluster_size(10000);
26
27 // (Optional, default 5000) Set the minimum number of inliers contained by a
28 // surface.
29 seg.set_min_surface_size(5000);
30
31 std::vector<SurfaceObjects> surface_objects;
32 bool success = seg.Segment(&surface_objects);
Demo
To run the demo:
rosrun surface_perception demo target_point_cloud_frame cloud_in:=input_point_cloud_topic
If target_point_cloud_frame is not provided, the point cloud will be processed in base_link.
surface_perception::SurfaceViz visualizes the result:
surface_perception_demo
This node runs the demo of surface_perceptionParameters
crop_min_x (float, default: 0.0)- The minimum x coordinate of the cropped input cloud.
- The minimum y coordinate of the cropped input cloud.
- The minimum z coordinate of the cropped input cloud.
- The maximum x coordinate of the cropped input cloud.
- The maximum y coordinate of the cropped input cloud.
- The maximum z coordinate of the cropped input cloud.
- The maximum degree difference between normal vector of a surface and the z-axis.
- The the maximum distance between the surface and its inliers.
- The maximum cluster distance for object extraction.
- The minimum number of points for an extracted object.
- The maximum number of points for an extracted object.
- The minimum number of points a surface must have.
- The minimum number of iteration that the surface exploration algorithm must go through.