EuclideanBasedClustering.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2011-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5  *
6  * ArmarX is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License version 2 as
8  * published by the Free Software Foundation.
9  *
10  * ArmarX is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  *
18  * @package VisionX
19  * @author Eren Aksoy ( eren dot aksoy at kit dot edu )
20  * @date 2015
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 
26 
27 
28 
30 {
31  labeledCloud.reset(new pcl::PointCloud<pcl::PointXYZRGBL>());
32 }
33 
34 pcl::PointCloud<pcl::PointXYZRGBL>::Ptr& EuclideanBasedClustering::GetLabeledPointCloud(pcl::PointCloud<PointO>::Ptr& CloudPtr)
35 {
36 
37  pcl::PointCloud<PointO>::Ptr filteredCloudPtr(new pcl::PointCloud<PointO>);
38  pcl::search::KdTree<PointO>::Ptr tree(new pcl::search::KdTree<PointO> ());
39  pcl::ModelCoefficients BackGroundCoefficients;
40 
41  std::cout << " inputCloudPtr size: " << CloudPtr->points.size() << std::endl;
42 
43  // apply pass through filtering in z axis
44  pcl::PassThrough<PointO> pass;
45  pass.setInputCloud(CloudPtr);
46  pass.setFilterFieldName("z");
47  pass.setFilterLimits(0.0, 1700);
48  pass.filter(*filteredCloudPtr);
49 
50  std::cout << " filteredCloudPtr size: " << filteredCloudPtr->points.size() << std::endl;
51 
52  // normal estimation
53  pcl::NormalEstimation<PointO, pcl::Normal> ne;
54  ne.setSearchMethod(tree);
55  ne.setKSearch(20); //Use 20 nearest neighbors
56 
57  // extract background
58  pcl::SACSegmentationFromNormals<PointO, pcl::Normal> segmentor;
59  segmentor.setOptimizeCoefficients(true);
60  segmentor.setModelType(pcl::SACMODEL_NORMAL_PLANE);
61  segmentor.setMethodType(pcl::SAC_RANSAC);
62  segmentor.setProbability(0.99);
63  segmentor.setEpsAngle(pcl::deg2rad(1.0));
64  segmentor.setRadiusLimits(0.0, 50.0);
65  segmentor.setMaxIterations(100);
66  segmentor.setDistanceThreshold(10); // Points at less than 1cm over the plane are part of the table
67 
68 
69  for (int i = 0; i < 4; i++)
70  {
71  pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
72  pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>);
73 
74  ne.setInputCloud(filteredCloudPtr);
75  ne.compute(*normals);
76 
77  segmentor.setInputCloud(filteredCloudPtr);
78  segmentor.setInputNormals(normals);
79  segmentor.segment(*inliers, BackGroundCoefficients);
80 
81  if (inliers->indices.size() > 10000)
82  {
83  // Extract the planar inliers from the input cloud
84  pcl::ExtractIndices<PointO> extract;
85  extract.setInputCloud(filteredCloudPtr);
86  extract.setIndices(inliers);
87  extract.setNegative(true);
88  extract.filter(*filteredCloudPtr);
89  }
90  else
91  {
92  break;
93  }
94  }
95 
96  std::cout << " filteredCloudPtr size after plane removal: " << filteredCloudPtr->points.size() << std::endl;
97 
98 
99  // clustering based on euclidean distances
100  tree->setInputCloud(filteredCloudPtr);
101  std::vector<pcl::PointIndices> ObjectClusters;
102  pcl::EuclideanClusterExtraction<PointO> ec;
103  ec.setClusterTolerance(50);
104  ec.setMinClusterSize(50);
105  ec.setMaxClusterSize(1000000);
106  ec.setInputCloud(filteredCloudPtr);
107  ec.setSearchMethod(tree);
108  ec.extract(ObjectClusters);
109 
110  std::cout << " Number of ObjectClusters: " << ObjectClusters.size() << std::endl;
111 
112  labeledCloud->points.clear();
113  int label = 0;
114 
115  for (std::vector<pcl::PointIndices>::const_iterator it = ObjectClusters.begin(); it != ObjectClusters.end(); ++it)
116  {
117  if (it->indices.size() < 3000)
118  {
119  continue;
120  }
121  label++;
122  std::cout << " ObjectClusters size: " << it->indices.size() << std::endl;
123  for (std::vector<int>::const_iterator pit = it->indices.begin(); pit != it->indices.end(); ++pit)
124  {
125  pcl::PointXYZRGBL currPoint;
126 
127  currPoint.x = filteredCloudPtr->points[*pit].x;
128  currPoint.y = filteredCloudPtr->points[*pit].y;
129  currPoint.z = filteredCloudPtr->points[*pit].z;
130  currPoint.rgba = filteredCloudPtr->points[*pit].rgba;
131  currPoint.label = label;
132 
133  labeledCloud->points.push_back(currPoint);
134  }
135  }
136 
137 
138  labeledCloud->height = 1;
139  labeledCloud->width = labeledCloud->points.size();
140 
141  return labeledCloud;
142 }
143 
144 
145 
EuclideanBasedClustering::GetLabeledPointCloud
pcl::PointCloud< pcl::PointXYZRGBL >::Ptr & GetLabeledPointCloud(pcl::PointCloud< PointO >::Ptr &CloudPtr)
Definition: EuclideanBasedClustering.cpp:34
EuclideanBasedClustering::EuclideanBasedClustering
EuclideanBasedClustering()
Definition: EuclideanBasedClustering.cpp:29
EuclideanBasedClustering.h