RG_Segmenter.h
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#pragma once
26
27#include <iostream>
28#include <vector>
29
30#include <pcl/features/normal_3d.h>
31#include <pcl/filters/passthrough.h>
32#include <pcl/io/pcd_io.h>
33#include <pcl/point_types.h>
34#include <pcl/search/kdtree.h>
35#include <pcl/search/search.h>
36#include <pcl/segmentation/region_growing.h>
37
39{
40public:
41 RGSegClass();
42
43 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr&
44 ApplyRegionGrowingSegmentation(pcl::PointCloud<pcl::PointXYZRGBA>::Ptr& CloudPtr);
45
46 void UpdateRegionGrowingSegmentationParameters(float SmoothnessThres, float CurvatureThres);
47
48
49private:
50 using PointT = pcl::PointXYZRGBA; // The point type used for input
51 using PointL = pcl::PointXYZL; // The point type used for input
52
53 pcl::PointCloud<PointT>::Ptr input_cloud_ptr;
54 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr output_colored_cloud;
55 pcl::PointCloud<PointL>::Ptr output_labeled_cloud;
56
57 float SmoothnessThreshold;
58 float CurvatureThreshold;
59
60 void RegionGrowingSegmenter();
61 void ConvertFromXYZRGBAtoXYZL();
62};
void UpdateRegionGrowingSegmentationParameters(float SmoothnessThres, float CurvatureThres)
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr & ApplyRegionGrowingSegmentation(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &CloudPtr)