29 labeledCloud.reset(
new pcl::PointCloud<pcl::PointXYZRGBL>());
32 pcl::PointCloud<pcl::PointXYZRGBL>::Ptr&
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;
40 std::cout <<
" inputCloudPtr size: " << CloudPtr->points.size() << std::endl;
43 pcl::PassThrough<PointO> pass;
44 pass.setInputCloud(CloudPtr);
45 pass.setFilterFieldName(
"z");
46 pass.setFilterLimits(0.0, 1700);
47 pass.filter(*filteredCloudPtr);
49 std::cout <<
" filteredCloudPtr size: " << filteredCloudPtr->points.size() << std::endl;
52 pcl::NormalEstimation<PointO, pcl::Normal> ne;
53 ne.setSearchMethod(tree);
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(
69 for (
int i = 0; i < 4; i++)
71 pcl::PointIndices::Ptr inliers(
new pcl::PointIndices);
72 pcl::PointCloud<pcl::Normal>::Ptr normals(
new pcl::PointCloud<pcl::Normal>);
74 ne.setInputCloud(filteredCloudPtr);
77 segmentor.setInputCloud(filteredCloudPtr);
78 segmentor.setInputNormals(normals);
79 segmentor.segment(*inliers, BackGroundCoefficients);
81 if (inliers->indices.size() > 10000)
84 pcl::ExtractIndices<PointO> extract;
85 extract.setInputCloud(filteredCloudPtr);
86 extract.setIndices(inliers);
87 extract.setNegative(
true);
88 extract.filter(*filteredCloudPtr);
96 std::cout <<
" filteredCloudPtr size after plane removal: " << filteredCloudPtr->points.size()
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);
111 std::cout <<
" Number of ObjectClusters: " << ObjectClusters.size() << std::endl;
113 labeledCloud->points.clear();
116 for (std::vector<pcl::PointIndices>::const_iterator it = ObjectClusters.begin();
117 it != ObjectClusters.end();
120 if (it->indices.size() < 3000)
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();
129 pcl::PointXYZRGBL currPoint;
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;
137 labeledCloud->points.push_back(currPoint);
142 labeledCloud->height = 1;
143 labeledCloud->width = labeledCloud->points.size();