The [[cob_3d_mapping_features]] package provides feature extraction and segmantation algorithms in order to describe point clouds. == ROS API == {{{ #!clearsilver CS/NodeAPI name = plane_extraction_nodelet desc = The `plane_extraction_nodelet` nodelet takes in <> messages and extracts planes using RANSAC. Convex hull polygons are calculated for each plane and publish as a <> sub{ 0.name = /point_cloud2 0.type = sensor_msgs/PointCloud2 0.desc = The input point cloud } pub{ 0.name = /shape_array 0.type = cob_3d_mapping_msgs/ShapeArray 0.desc = The extracted hull polygons 1.name = /visualization_marker 1.type = visualization_msgs/Marker 1.desc = The extracted hull polygons as Marker for RViz } param{ 0.name = ~plane_constraint 0.type = int 0.default = 0 0.desc = Constrain the planes extracted (0=NONE, 1=HORIZONTAL, 2=VERTICAL) 1.name = ~voxel_leafsize 1.type = double 1.default = 0.04 1.desc = Voxel resolution for down-sampling (in m) 2.name = ~passthrough_min_z 2.type = double 2.default = -0.1 2.desc = Minimum z value for pass-through filter (in m) 3.name = ~passthrough_max_z 3.type = double 3.default = 3 3.desc = Maximum z value for pass-through filter (in m) 4.name = ~cluster_tolerance 4.type = double 4.default = 0.05 4.desc = Minimum distance between points for clustering (in m) 5.name = ~min_plane_size 5.type = int 5.default = 50 5.desc = Minimum number of inliers for planes 5.name = ~alpha 5.type = double 5.default = 0.1 5.desc = Alpha value for convex hull 6.name = ~target_frame 6.type = string 6.default = map 6.desc = The frame input data is transformed to 7.name = ~mode_action 7.type = bool 7.default = false 7.desc = Use action or topic mode 8.name = ~save_to_file 8.type = bool 8.default = false 8.desc = Flag for saving the map as a PCD file after each update (for debugging) 9.name = ~file_path 9.type = string 9.default = /tmp 9.desc = File path for saving the map } req_tf{ } prov_tf{ } }}} == Usage/Examples == === Plane Extraction === Launch the plane extraction {{{ roslaunch cob_3d_mapping_features extract_planes.launch }}}