The cob_3d_mapping_features package provides feature extraction and segmantation algorithms in order to describe point clouds.

ROS API

plane_extraction_nodelet

The plane_extraction_nodelet nodelet takes in sensor_msgs/PointCloud2 messages and extracts planes using RANSAC. Convex hull polygons are calculated for each plane and publish as a cob_3d_mapping_msgs/ShapeArray

Subscribed Topics

/point_cloud2 (sensor_msgs/PointCloud2)
  • The input point cloud

Published Topics

/shape_array (cob_3d_mapping_msgs/ShapeArray)
  • The extracted hull polygons
/visualization_marker (visualization_msgs/Marker)
  • The extracted hull polygons as Marker for RViz

Parameters

~plane_constraint (int, default: 0)
  • Constrain the planes extracted (0=NONE, 1=HORIZONTAL, 2=VERTICAL)
~voxel_leafsize (double, default: 0.04)
  • Voxel resolution for down-sampling (in m)
~passthrough_min_z (double, default: -0.1)
  • Minimum z value for pass-through filter (in m)
~passthrough_max_z (double, default: 3)
  • Maximum z value for pass-through filter (in m)
~cluster_tolerance (double, default: 0.05)
  • Minimum distance between points for clustering (in m)
~alpha (double, default: 0.1)
  • Alpha value for convex hull
~target_frame (string, default: map)
  • The frame input data is transformed to
~mode_action (bool, default: false)
  • Use action or topic mode
~save_to_file (bool, default: false)
  • Flag for saving the map as a PCD file after each update (for debugging)
~file_path (string, default: /tmp)
  • File path for saving the map

Usage/Examples

Plane Extraction

Launch the plane extraction

roslaunch cob_3d_mapping_features extract_planes.launch

Wiki: cob_3d_mapping_features (last edited 2012-04-18 13:34:35 by GeorgArbeiter)