32 #include <Eigen/Eigen>    33 #include <boost/lexical_cast.hpp>    48   double cluster_tolerance;
    49   nh.
param<
double>(
"cluster_tolerance", cluster_tolerance, 0.01);
    54   nh.
param<
int>(
"cluster_min_size", cluster_min_size, 50);
    58   double leaf_size, llimit, ulimit;
    60   nh.
param<
double>(
"voxel_leaf_size", leaf_size, 0.005);
    61   nh.
param<
double>(
"voxel_limit_min", llimit, 0.0);
    62   nh.
param<
double>(
"voxel_limit_max", ulimit, 1.8);
    63   nh.
param<std::string>(
"voxel_field_name", field, 
"z");
    64   voxel_grid_.setLeafSize(leaf_size, leaf_size, leaf_size);
    69   segment_.setOptimizeCoefficients(
true);
    70   segment_.setModelType(pcl::SACMODEL_PLANE);
    72   segment_.setDistanceThreshold(cluster_tolerance);
    76   const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud,
    77   std::vector<grasping_msgs::Object>& objects,
    78   std::vector<grasping_msgs::Object>& supports,
    79   pcl::PointCloud<pcl::PointXYZRGB>& object_cloud,
    80   pcl::PointCloud<pcl::PointXYZRGB>& support_cloud,
    83   ROS_INFO(
"object support segmentation starting...");
    86   pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_filtered(
new pcl::PointCloud<pcl::PointXYZRGB>);
    90                   "Filtered for transformed Z, now %d points.", static_cast<int>(cloud_filtered->points.size()));
    93   pcl::PointCloud<pcl::PointXYZRGB>::Ptr non_horizontal_planes(
new pcl::PointCloud<pcl::PointXYZRGB>);
    94   std::vector<pcl::ModelCoefficients::Ptr> plane_coefficients;  
    95   int thresh = cloud_filtered->points.size()/8;
    96   while (cloud_filtered->points.size() > 500)
    98     pcl::PointIndices::Ptr inliers(
new pcl::PointIndices);
    99     pcl::ModelCoefficients::Ptr coefficients(
new pcl::ModelCoefficients);
   102     segment_.setInputCloud(cloud_filtered);
   103     segment_.segment(*inliers, *coefficients);
   104     if (inliers->indices.size() < (size_t) thresh)  
   106       ROS_DEBUG_NAMED(
"object_support_segmentation", 
"No more planes to remove.");
   111     pcl::PointCloud<pcl::PointXYZRGB> plane;
   112     pcl::ExtractIndices<pcl::PointXYZRGB> extract;
   113     extract.setInputCloud(cloud_filtered);
   114     extract.setIndices(inliers);
   115     extract.setNegative(
false);
   116     extract.filter(plane);
   119     Eigen::Vector3f normal(coefficients->values[0], coefficients->values[1], coefficients->values[2]);
   120     float angle = acos(Eigen::Vector3f::UnitZ().
dot(normal));
   124                       "Removing a plane with %d points.", static_cast<int>(inliers->indices.size()));
   127       grasping_msgs::Object object;
   130       object.name = std::string(
"surface") + boost::lexical_cast<std::string>(supports.size());
   132       shape_msgs::SolidPrimitive box;
   133       geometry_msgs::Pose 
pose;
   135       object.primitives.push_back(box);
   136       object.primitive_poses.push_back(pose);
   138       for (
int i = 0; i < 4; ++i)
   139         object.surface.coef[i] = coefficients->values[i];
   142       object.header.frame_id = cloud->header.frame_id;
   144       supports.push_back(
object);
   149                         "Adding support cluster of size %d.", static_cast<int>(plane.points.size()));
   150         float hue = (360.0 / 8) * supports.size();
   152         support_cloud += plane;
   156       plane_coefficients.push_back(coefficients);
   161       ROS_DEBUG_NAMED(
"object_support_segmentation", 
"Plane is not horizontal");
   162       *non_horizontal_planes += plane;
   166     extract.setNegative(
true);
   167     extract.filter(*cloud_filtered);
   170                   "Cloud now %d points.", static_cast<int>(cloud_filtered->points.size()));
   173   *cloud_filtered += *non_horizontal_planes;
   176   std::vector<pcl::PointIndices> clusters;
   180                   "Extracted %d clusters.", static_cast<int>(clusters.size()));
   183   for (
size_t i= 0; i < clusters.size(); i++)
   186     pcl::PointCloud<pcl::PointXYZRGB> new_cloud;
   187     extract_indices_.setIndices(pcl::PointIndicesPtr(
new pcl::PointIndices(clusters[i])));
   191     Eigen::Vector4f centroid;
   192     pcl::compute3DCentroid(new_cloud, centroid);
   195     int support_plane_index = -1;
   196     double support_plane_distance = 1000.0;
   197     for (
int p = 0; p < plane_coefficients.size(); ++p)
   200       if (distance > 0.0 && distance < support_plane_distance)
   202         support_plane_distance = distance;
   203         support_plane_index = p;
   207     if (support_plane_index == -1)
   210                       "No support plane found for object");
   215     grasping_msgs::Object object;
   217     object.support_surface = std::string(
"surface") + boost::lexical_cast<std::string>(support_plane_index);
   219     shape_msgs::SolidPrimitive box;
   220     geometry_msgs::Pose 
pose;
   221     pcl::PointCloud<pcl::PointXYZRGB> projected_cloud;
   222     extractShape(new_cloud, plane_coefficients[support_plane_index], projected_cloud, box, pose);
   224     object.primitives.push_back(box);
   225     object.primitive_poses.push_back(pose);
   228     object.header.frame_id = cloud->header.frame_id;
   230     objects.push_back(
object);
   235                       "Adding an object cluster of size %d.", static_cast<int>(new_cloud.points.size()));
   236       float hue = (360.0 / clusters.size()) * i;
   238       object_cloud += new_cloud;
   242   ROS_INFO(
"object support segmentation done processing.");
 ObjectSupportSegmentation(ros::NodeHandle &nh)
Constructor, loads pipeline using ROS parameters. 
pcl::VoxelGrid< pcl::PointXYZRGB > voxel_grid_
double distancePointToPlane(const PointT &point, const pcl::ModelCoefficients::Ptr plane)
Get distance from point to plane. 
void colorizeCloud(pcl::PointCloud< pcl::PointXYZRGB > &cloud, float hue)
Update rgb component of an XYZRGB cloud to a new HSV color. 
pcl::SACSegmentation< pcl::PointXYZRGB > segment_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
#define ROS_DEBUG_NAMED(name,...)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool extractShape(const pcl::PointCloud< pcl::PointXYZRGB > &input, pcl::PointCloud< pcl::PointXYZRGB > &output, shape_msgs::SolidPrimitive &shape, geometry_msgs::Pose &pose)
Find the smallest shape primitive we can fit around this object. 
bool extractUnorientedBoundingBox(const pcl::PointCloud< pcl::PointXYZRGB > &input, shape_msgs::SolidPrimitive &shape, geometry_msgs::Pose &pose)
Find a bounding box around a cloud. This method does not attempt to find best orientation and so the ...
pcl::EuclideanClusterExtraction< pcl::PointXYZRGB > extract_clusters_
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
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. 
pcl::ExtractIndices< pcl::PointXYZRGB > extract_indices_