region_growing_segmentation_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Ryohei Ueda and JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
37 
38 #include "jsk_recognition_msgs/ClusterPointIndices.h"
39 #include <pcl/segmentation/impl/region_growing.hpp>
41 
43 
44 namespace jsk_pcl_ros
45 {
46 
48  {
49  ConnectionBasedNodelet::onInit();
50  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51  dynamic_reconfigure::Server<Config>::CallbackType f =
52  boost::bind (&RegionGrowingSegmentation::configCallback, this, _1, _2);
53  srv_->setCallback (f);
54  pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output", 1);
56  }
57 
59  {
60  sub_ = pnh_->subscribe("input", 1, &RegionGrowingSegmentation::segment, this);
61  }
62 
64  {
65  sub_.shutdown();
66  }
67 
68  void RegionGrowingSegmentation::configCallback(Config &config, uint32_t level)
69  {
70  boost::mutex::scoped_lock lock(mutex_);
71 
72  if (number_of_neighbors_ != config.number_of_neighbors) {
73  number_of_neighbors_ = config.number_of_neighbors;
74  }
75  if (min_size_ != config.min_size) {
76  min_size_ = config.min_size;
77  }
78  if (max_size_ != config.max_size) {
79  max_size_ = config.max_size;
80  }
81  if (smoothness_threshold_ != config.smoothness_threshold) {
82  smoothness_threshold_ = config.smoothness_threshold;
83  }
84  if (curvature_threshold_ != config.curvature_threshold) {
85  curvature_threshold_ = config.curvature_threshold;
86  }
87  }
88 
89  void RegionGrowingSegmentation::segment(const sensor_msgs::PointCloud2::ConstPtr& msg)
90  {
91  boost::mutex::scoped_lock lock(mutex_);
92  pcl::search::Search<pcl::PointNormal>::Ptr tree = boost::shared_ptr<pcl::search::Search<pcl::PointNormal> > (new pcl::search::KdTree<pcl::PointNormal>);
93  pcl::PointCloud<pcl::PointNormal> cloud;
94  pcl::fromROSMsg(*msg, cloud);
95 
96  pcl::RegionGrowing<pcl::PointNormal, pcl::PointNormal> reg;
97  reg.setMinClusterSize (min_size_);
98  reg.setMaxClusterSize (max_size_);
99  reg.setSearchMethod (tree);
100  reg.setNumberOfNeighbours (number_of_neighbors_);
101  reg.setInputCloud (cloud.makeShared());
102  //reg.setIndices (indices);
103  reg.setInputNormals (cloud.makeShared());
104  reg.setSmoothnessThreshold (smoothness_threshold_);
105  reg.setCurvatureThreshold (curvature_threshold_);
106 
107  std::vector <pcl::PointIndices> clusters;
108  reg.extract (clusters);
109 
110  jsk_recognition_msgs::ClusterPointIndices output;
111  output.header = msg->header;
112 
113  for (size_t i = 0; i < clusters.size(); i++) {
114  PCLIndicesMsg indices;
115  indices.header = msg->header;
116  indices.indices = clusters[i].indices;
117  output.cluster_indices.push_back(indices);
118  }
119  pub_.publish(output);
120  }
121 
122 }
123 
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::RegionGrowingSegmentation, nodelet::Nodelet)
virtual void configCallback(Config &config, uint32_t level)
void publish(const boost::shared_ptr< M > &message) const
jsk_pcl_ros::RegionGrowingSegmentationConfig Config
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
void output(int index, double value)
boost::shared_ptr< ros::NodeHandle > pnh_
#define reg
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &msg)
pcl::PointIndices PCLIndicesMsg
cloud


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47