31 labeledCloud.reset(
new pcl::PointCloud<pcl::PointXYZRGBL>());
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;
41 std::cout <<
" inputCloudPtr size: " << CloudPtr->points.size() << std::endl;
44 pcl::PassThrough<PointO> pass;
45 pass.setInputCloud(CloudPtr);
46 pass.setFilterFieldName(
"z");
47 pass.setFilterLimits(0.0, 1700);
48 pass.filter(*filteredCloudPtr);
50 std::cout <<
" filteredCloudPtr size: " << filteredCloudPtr->points.size() << std::endl;
53 pcl::NormalEstimation<PointO, pcl::Normal> ne;
54 ne.setSearchMethod(tree);
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);
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() << std::endl;
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);
110 std::cout <<
" Number of ObjectClusters: " << ObjectClusters.size() << std::endl;
112 labeledCloud->points.clear();
115 for (std::vector<pcl::PointIndices>::const_iterator it = ObjectClusters.begin(); it != ObjectClusters.end(); ++it)
117 if (it->indices.size() < 3000)
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)
125 pcl::PointXYZRGBL currPoint;
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;
133 labeledCloud->points.push_back(currPoint);
138 labeledCloud->height = 1;
139 labeledCloud->width = labeledCloud->points.size();