Note: This tutorial assumes that you have completed the previous tutorials: ExtractPolygonalPrismData segmentation.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

ExtractPolygonalPrismData segmentation

Description: ExtractPolygonalPrismData segmentation

Tutorial Level:

Contents

The following launch file starts a nodelet manager together with a VoxelGrid PCL filter nodelet. The input PointCloud2 topic is set to /scene_pointcloud2.

The default filtering values are set to filter data on the z-axis between 0.01 and 1.5 meters, and downsample the data with a leaf size of 0.01 meters.

The segmentation is performed by first estimating surface normals at each point for a support of 0.015 meters, and then using a RANSAC-based estimator for fitting planes with a threshold of 0.1 meters, and a normal deviation of ~5 degrees (0.09 radians).

The convex hull of the projected planar inliers is estimated and an ExtractPolygonalPrismData nodelet is used to extract all point indices between 0 and 0.5 meters from the planar table support, with their projections falling inside the convex hull.

   1 <launch>
   2   <node pkg="nodelet" type="nodelet" name="pcl_manager" args="manager" output="screen" />
   3 
   4   <!-- Run a VoxelGrid filter to clean NaNs and downsample the data -->
   5   <node pkg="nodelet" type="nodelet" name="voxel_grid" args="load pcl/VoxelGrid pcl_manager" output="screen">
   6     <remap from="~input" to="/scene_pointcloud2" />
   7     <rosparam>
   8       filter_field_name: z
   9       filter_limit_min: 0.01
  10       filter_limit_max: 1.5
  11       filter_limit_negative: False
  12       leaf_size: 0.01
  13     </rosparam>
  14   </node>
  15 
  16   <!-- Estimate point normals -->
  17   <node pkg="nodelet" type="nodelet" name="normal_estimation" args="load pcl/NormalEstimation pcl_manager" output="screen">
  18     <remap from="~input" to="/voxel_grid/output" />
  19     <rosparam>
  20       # -[ Mandatory parameters
  21       k_search: 0
  22       radius_search: 0.015
  23       # Set the spatial locator. Possible values are: 0 (ANN), 1 (FLANN), 2 (organized)
  24       spatial_locator: 0
  25     </rosparam>
  26   </node>
  27 
  28   <!-- Segment the table plane -->
  29   <node pkg="nodelet" type="nodelet" name="planar_segmentation" args="load pcl/SACSegmentationFromNormals pcl_manager" output="screen">
  30     <remap from="~input"   to="/voxel_grid/output" />
  31     <remap from="~normals" to="/normal_estimation/output" />
  32     <rosparam>
  33       # -[ Mandatory parameters
  34       model_type: 11
  35       distance_threshold: 0.1
  36       max_iterations: 1000
  37       method_type: 0
  38       optimize_coefficients: true
  39       normal_distance_weight: 0.1
  40       eps_angle: 0.09
  41     </rosparam>
  42   </node>
  43 
  44   <node pkg="nodelet" type="nodelet" name="extract_plane_indices" args="load pcl/ExtractIndices pcl_manager" output="screen">
  45     <remap from="~input"   to="/voxel_grid/output" />
  46     <remap from="~indices" to="/planar_segmentation/inliers" />
  47     <rosparam>
  48       negative: true
  49     </rosparam>
  50   </node>
  51 
  52   <!-- Project the planar inliers -->
  53   <node pkg="nodelet" type="nodelet" name="project_plane_inliers" args="load pcl/ProjectInliers pcl_manager" output="screen">
  54    <remap from="~input"   to="/voxel_grid/output" />
  55    <remap from="~indices" to="/planar_segmentation/inliers" />
  56    <remap from="~model"   to="/planar_segmentation/model" />
  57    <rosparam>
  58      model_type: 11
  59      copy_all_data: false
  60      copy_all_fields: true
  61    </rosparam>
  62   </node>
  63 
  64   <!-- Compute the convex hull -->
  65   <node pkg="nodelet" type="nodelet" name="convex_hull" args="load pcl/ConvexHull2D pcl_manager" output="screen">
  66     <remap from="~input"   to="/project_plane_inliers/output" />
  67   </node>
  68 
  69   <!-- Extract the object clusters using a polygonal prism -->
  70   <node pkg="nodelet" type="nodelet" name="extract_objects_table" args="load pcl/ExtractPolygonalPrismData pcl_manager" output="screen">
  71    <remap from="~input"         to="/extract_plane_indices/output" />
  72    <remap from="~planar_hull"   to="/convex_hull/output" />
  73    <rosparam>
  74      height_min: 0
  75      height_max: 0.5
  76    </rosparam>
  77   </node>
  78 
  79   <node pkg="nodelet" type="nodelet" name="extract_objects_indices" args="load pcl/ExtractIndices pcl_manager" output="screen">
  80     <!-- Extract_plane_indices needs to be negated for this work -->
  81     <remap from="~input"   to="/extract_plane_indices/output" />
  82     <remap from="~indices" to="/extract_objects_table/output" />
  83     <rosparam>
  84       negative: false
  85     </rosparam>
  86   </node>
  87 </launch>

Wiki: pcl_ros/Tutorials/ExtractPolygonalPrismData segmentation (last edited 2010-10-31 19:12:55 by RaduBogdanRusu)