38 #include "jsk_recognition_msgs/ClusterPointIndices.h"
39 #include <pcl/segmentation/impl/region_growing.hpp>
49 ConnectionBasedNodelet::onInit();
50 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51 dynamic_reconfigure::Server<Config>::CallbackType
f =
53 srv_->setCallback (
f);
54 pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_,
"output", 1);
92 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
93 pcl::search::Search<pcl::PointNormal>::Ptr
tree(
new pcl::search::KdTree<pcl::PointNormal>());
97 pcl::PointCloud<pcl::PointNormal>
cloud;
100 pcl::RegionGrowing<pcl::PointNormal, pcl::PointNormal>
reg;
103 reg.setSearchMethod (tree);
105 reg.setInputCloud (
cloud.makeShared());
107 reg.setInputNormals (
cloud.makeShared());
111 std::vector <pcl::PointIndices> clusters;
112 reg.extract (clusters);
114 jsk_recognition_msgs::ClusterPointIndices output;
115 output.header =
msg->header;
117 for (
size_t i = 0;
i < clusters.size();
i++) {
119 indices.header =
msg->header;
120 indices.indices = clusters[
i].indices;
121 output.cluster_indices.push_back(indices);