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
28{
29 labeledCloud.reset(new pcl::PointCloud<pcl::PointXYZRGBL>());
30}
31
32pcl::PointCloud<pcl::PointXYZRGBL>::Ptr&
33EuclideanBasedClustering::GetLabeledPointCloud(pcl::PointCloud<PointO>::Ptr& CloudPtr)
34{
35
36 pcl::PointCloud<PointO>::Ptr filteredCloudPtr(new pcl::PointCloud<PointO>);
37 pcl::search::KdTree<PointO>::Ptr tree(new pcl::search::KdTree<PointO>());
38 pcl::ModelCoefficients BackGroundCoefficients;
39
40 std::cout << " inputCloudPtr size: " << CloudPtr->points.size() << std::endl;
41
42 // apply pass through filtering in z axis
43 pcl::PassThrough<PointO> pass;
44 pass.setInputCloud(CloudPtr);
45 pass.setFilterFieldName("z");
46 pass.setFilterLimits(0.0, 1700);
47 pass.filter(*filteredCloudPtr);
48
49 std::cout << " filteredCloudPtr size: " << filteredCloudPtr->points.size() << std::endl;
50
51 // normal estimation
52 pcl::NormalEstimation<PointO, pcl::Normal> ne;
53 ne.setSearchMethod(tree);
54 ne.setKSearch(20); //Use 20 nearest neighbors
55
56 // extract background
57 pcl::SACSegmentationFromNormals<PointO, pcl::Normal> segmentor;
58 segmentor.setOptimizeCoefficients(true);
59 segmentor.setModelType(pcl::SACMODEL_NORMAL_PLANE);
60 segmentor.setMethodType(pcl::SAC_RANSAC);
61 segmentor.setProbability(0.99);
62 segmentor.setEpsAngle(pcl::deg2rad(1.0));
63 segmentor.setRadiusLimits(0.0, 50.0);
64 segmentor.setMaxIterations(100);
65 segmentor.setDistanceThreshold(
66 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()
97 << std::endl;
98
99
100 // clustering based on euclidean distances
101 tree->setInputCloud(filteredCloudPtr);
102 std::vector<pcl::PointIndices> ObjectClusters;
103 pcl::EuclideanClusterExtraction<PointO> ec;
104 ec.setClusterTolerance(50);
105 ec.setMinClusterSize(50);
106 ec.setMaxClusterSize(1000000);
107 ec.setInputCloud(filteredCloudPtr);
108 ec.setSearchMethod(tree);
109 ec.extract(ObjectClusters);
110
111 std::cout << " Number of ObjectClusters: " << ObjectClusters.size() << std::endl;
112
113 labeledCloud->points.clear();
114 int label = 0;
115
116 for (std::vector<pcl::PointIndices>::const_iterator it = ObjectClusters.begin();
117 it != ObjectClusters.end();
118 ++it)
119 {
120 if (it->indices.size() < 3000)
121 {
122 continue;
123 }
124 label++;
125 std::cout << " ObjectClusters size: " << it->indices.size() << std::endl;
126 for (std::vector<int>::const_iterator pit = it->indices.begin(); pit != it->indices.end();
127 ++pit)
128 {
129 pcl::PointXYZRGBL currPoint;
130
131 currPoint.x = filteredCloudPtr->points[*pit].x;
132 currPoint.y = filteredCloudPtr->points[*pit].y;
133 currPoint.z = filteredCloudPtr->points[*pit].z;
134 currPoint.rgba = filteredCloudPtr->points[*pit].rgba;
135 currPoint.label = label;
136
137 labeledCloud->points.push_back(currPoint);
138 }
139 }
140
141
142 labeledCloud->height = 1;
143 labeledCloud->width = labeledCloud->points.size();
144
145 return labeledCloud;
146}
pcl::PointCloud< pcl::PointXYZRGBL >::Ptr & GetLabeledPointCloud(pcl::PointCloud< PointO >::Ptr &CloudPtr)