Public Member Functions | Private Attributes | List of all members
simple_grasping::ObjectSupportSegmentation Class Reference

Class that segments a point cloud into objects and supporting surfaces. More...

#include <object_support_segmentation.h>

Public Member Functions

 ObjectSupportSegmentation (ros::NodeHandle &nh)
 Constructor, loads pipeline using ROS parameters. More...
 
bool segment (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, std::vector< grasping_msgs::Object > &objects, std::vector< grasping_msgs::Object > &supports, pcl::PointCloud< pcl::PointXYZRGB > &object_cloud, pcl::PointCloud< pcl::PointXYZRGB > &support_cloud, bool output_clouds)
 Split a cloud into objects and supporting surfaces. More...
 

Private Attributes

pcl::EuclideanClusterExtraction< pcl::PointXYZRGB > extract_clusters_
 
pcl::ExtractIndices< pcl::PointXYZRGB > extract_indices_
 
pcl::SACSegmentation< pcl::PointXYZRGB > segment_
 
pcl::VoxelGrid< pcl::PointXYZRGB > voxel_grid_
 

Detailed Description

Class that segments a point cloud into objects and supporting surfaces.

Definition at line 51 of file object_support_segmentation.h.

Constructor & Destructor Documentation

simple_grasping::ObjectSupportSegmentation::ObjectSupportSegmentation ( ros::NodeHandle nh)

Constructor, loads pipeline using ROS parameters.

Parameters
nhNode handle to use for accessing parameters.

Definition at line 43 of file object_support_segmentation.cpp.

Member Function Documentation

bool simple_grasping::ObjectSupportSegmentation::segment ( const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &  cloud,
std::vector< grasping_msgs::Object > &  objects,
std::vector< grasping_msgs::Object > &  supports,
pcl::PointCloud< pcl::PointXYZRGB > &  object_cloud,
pcl::PointCloud< pcl::PointXYZRGB > &  support_cloud,
bool  output_clouds 
)

Split a cloud into objects and supporting surfaces.

Parameters
cloudThe point cloud to segment. This cloud should already be transformed into a coordinate frame where XY plane is horizontal.
objectsThe vector to fill in with objects found.
supportsThe vector to fill in with support surfaces found.
object_cloudA colored cloud of objects found (if output_clouds).
support_cloudA colored cloud of supports found (if output_clouds).

Definition at line 75 of file object_support_segmentation.cpp.

Member Data Documentation

pcl::EuclideanClusterExtraction<pcl::PointXYZRGB> simple_grasping::ObjectSupportSegmentation::extract_clusters_
private

Definition at line 80 of file object_support_segmentation.h.

pcl::ExtractIndices<pcl::PointXYZRGB> simple_grasping::ObjectSupportSegmentation::extract_indices_
private

Definition at line 81 of file object_support_segmentation.h.

pcl::SACSegmentation<pcl::PointXYZRGB> simple_grasping::ObjectSupportSegmentation::segment_
private

Definition at line 79 of file object_support_segmentation.h.

pcl::VoxelGrid<pcl::PointXYZRGB> simple_grasping::ObjectSupportSegmentation::voxel_grid_
private

Definition at line 78 of file object_support_segmentation.h.


The documentation for this class was generated from the following files:


simple_grasping
Author(s): Michael Ferguson
autogenerated on Thu Jan 14 2021 03:20:55