(!) 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.

ConvexHull planar surface reconstruction

Description: ConvexHull planar surface reconstruction

Tutorial Level: BEGINNER

Contents

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

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 published on the /convex_hull/output topic.

   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="/camera/depth/points" />
   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 
  35       # model_type:
  36       # 0: SACMODEL_PLANE
  37       # 1: SACMODEL_LINE
  38       # 2: SACMODEL_CIRCLE2D
  39       # 3: SACMODEL_CIRCLE3D
  40       # 4: SACMODEL_SPHERE
  41       # 5: SACMODEL_CYLINDER
  42       # 6: SACMODEL_CONE
  43       # 7: SACMODEL_TORUS
  44       # 8: SACMODEL_PARALLEL_LINE
  45       # 9: SACMODEL_PERPENDICULAR_PLANE
  46       # 10: SACMODEL_PARALLEL_LINES
  47       # 11: SACMODEL_NORMAL_PLANE
  48       # 12: SACMODEL_NORMAL_SPHERE
  49       # 13: SACMODEL_REGISTRATION
  50       # 14: SACMODEL_REGISTRATION_2D
  51       # 15: SACMODEL_PARALLEL_PLANE
  52       # 16: SACMODEL_NORMAL_PARALLEL_PLANE
  53       # 17: SACMODEL_STICK
  54       model_type: 11
  55       distance_threshold: 0.01
  56       max_iterations: 1000
  57       method_type: 0
  58       optimize_coefficients: true
  59       normal_distance_weight: 0.1
  60       eps_angle: 0.09
  61     </rosparam>
  62   </node>
  63 
  64   <node pkg="nodelet" type="nodelet" name="extract_plane_indices" args="load pcl/ExtractIndices pcl_manager" output="screen">
  65     <remap from="~input"   to="/voxel_grid/output" />
  66     <remap from="~indices" to="/planar_segmentation/inliers" />
  67     <rosparam>
  68       negative: true
  69     </rosparam>
  70   </node>
  71 
  72   <!-- Project the planar inliers -->
  73   <node pkg="nodelet" type="nodelet" name="project_plane_inliers" args="load pcl/ProjectInliers pcl_manager" output="screen">
  74    <remap from="~input"   to="/voxel_grid/output" />
  75    <remap from="~indices" to="/planar_segmentation/inliers" />
  76    <remap from="~model"   to="/planar_segmentation/model" />
  77    <rosparam>
  78      model_type: 11
  79      copy_all_data: false
  80      copy_all_fields: true
  81    </rosparam>
  82   </node>
  83 
  84   <!-- Compute the convex hull -->
  85   <node pkg="nodelet" type="nodelet" name="convex_hull" args="load pcl/ConvexHull2D pcl_manager" output="screen">
  86     <remap from="~input"   to="/project_plane_inliers/output" />
  87   </node>
  88 </launch>

pic1 display view

Wiki: pcl_ros/Tutorials/ConvexHull planar surface reconstruction (last edited 2014-09-30 08:41:45 by Iori Yanokura)