Class that segments a point cloud into objects and supporting surfaces.
More...
#include <object_support_segmentation.h>
Class that segments a point cloud into objects and supporting surfaces.
Definition at line 51 of file object_support_segmentation.h.
simple_grasping::ObjectSupportSegmentation::ObjectSupportSegmentation |
( |
ros::NodeHandle & |
nh | ) |
|
Constructor, loads pipeline using ROS parameters.
- Parameters
-
nh | Node handle to use for accessing parameters. |
Definition at line 43 of file object_support_segmentation.cpp.
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
-
cloud | The point cloud to segment. This cloud should already be transformed into a coordinate frame where XY plane is horizontal. |
objects | The vector to fill in with objects found. |
supports | The vector to fill in with support surfaces found. |
object_cloud | A colored cloud of objects found (if output_clouds). |
support_cloud | A colored cloud of supports found (if output_clouds). |
Definition at line 75 of file object_support_segmentation.cpp.
pcl::ExtractIndices<pcl::PointXYZRGB> simple_grasping::ObjectSupportSegmentation::extract_indices_ |
|
private |
pcl::VoxelGrid<pcl::PointXYZRGB> simple_grasping::ObjectSupportSegmentation::voxel_grid_ |
|
private |
The documentation for this class was generated from the following files: