RG_Segmenter.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 
25 #include "RG_Segmenter.h"
26 
28 {
29  /// Create variables needed for preparations
30  input_cloud_ptr.reset(new pcl::PointCloud<PointT>);
31  output_colored_cloud.reset(new pcl::PointCloud<PointT>);
32  output_labeled_cloud.reset(new pcl::PointCloud<PointL>);
33 
34  SmoothnessThreshold = 30.0f;
35  CurvatureThreshold = 10.0f;
36 }
37 //---------------------------------------------------------------------------------------------------------------------//
38 
39 pcl::PointCloud< pcl::PointXYZRGBA >::Ptr& RGSegClass::ApplyRegionGrowingSegmentation(pcl::PointCloud<pcl::PointXYZRGBA>::Ptr& CloudPtr)
40 {
41  // copy original points to the cloud
42  pcl::copyPointCloud(*CloudPtr, *input_cloud_ptr);
43 
44  RegionGrowingSegmenter();
45 
46  return output_colored_cloud;
47 }
48 //---------------------------------------------------------------------------------------------------------------------//
49 
50 void RGSegClass::RegionGrowingSegmenter()
51 {
52  pcl::search::Search<PointT>::Ptr tree = pcl::search::Search<PointT>::Ptr(new pcl::search::KdTree<PointT>);
53  pcl::PointCloud <pcl::Normal>::Ptr normals(new pcl::PointCloud <pcl::Normal>);
54  pcl::NormalEstimation<PointT, pcl::Normal> normal_estimator;
55  normal_estimator.setSearchMethod(tree);
56  normal_estimator.setInputCloud(input_cloud_ptr);
57  normal_estimator.setKSearch(50);
58  normal_estimator.compute(*normals);
59 
60  /*
61  pcl::IndicesPtr indices (new std::vector <int>);
62  pcl::PassThrough<PointT> pass;
63  pass.setInputCloud (input_cloud_ptr);
64  pass.setFilterFieldName ("y");
65  pass.setFilterLimits (0.0, 5000.0);
66  pass.filter (*indices);
67  */
68 
69  pcl::RegionGrowing<PointT, pcl::Normal> reg;
70  reg.setMinClusterSize(50);
71  reg.setMaxClusterSize(1000000);
72  reg.setSearchMethod(tree);
73  reg.setNumberOfNeighbours(25);
74  reg.setInputCloud(input_cloud_ptr);
75  //reg.setIndices (indices);
76  reg.setInputNormals(normals);
77  reg.setSmoothnessThreshold(SmoothnessThreshold / 180.0 * M_PI);
78  reg.setCurvatureThreshold(CurvatureThreshold);
79 
80  std::vector <pcl::PointIndices> clusters;
81  reg.extract(clusters);
82 
83  std::cout << "=RG Segmenter: Number of clusters is " << clusters.size() << std::endl;
84 
85  output_colored_cloud = reg.getColoredCloudRGBA();
86 
87 }
88 //---------------------------------------------------------------------------------------------------------------------//
89 
90 void RGSegClass::UpdateRegionGrowingSegmentationParameters(float SmoothnessThres, float CurvatureThres)
91 {
92  SmoothnessThreshold = SmoothnessThres;
93  CurvatureThreshold = CurvatureThres;
94 
95  std::cout << "=RG Segmenter: Parameters updated! >> SmoothnessThreshold : " << SmoothnessThreshold << " CurvatureThreshold: " << CurvatureThreshold << std::endl;
96 }
97 //---------------------------------------------------------------------------------------------------------------------//
98 
99 void RGSegClass::ConvertFromXYZRGBAtoXYZL()
100 {
101  // to be done!...
102 
103 
104 
105 }
106 //---------------------------------------------------------------------------------------------------------------------//
107 
RGSegClass::RGSegClass
RGSegClass()
Definition: RG_Segmenter.cpp:27
M_PI
#define M_PI
Definition: MathTools.h:17
RGSegClass::ApplyRegionGrowingSegmentation
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr & ApplyRegionGrowingSegmentation(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &CloudPtr)
Definition: RG_Segmenter.cpp:39
RGSegClass::UpdateRegionGrowingSegmentationParameters
void UpdateRegionGrowingSegmentationParameters(float SmoothnessThres, float CurvatureThres)
Definition: RG_Segmenter.cpp:90
RG_Segmenter.h