convex_connected_voxels_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, 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 namespace jsk_pcl_ros
39 {
41  {
42  DiagnosticNodelet::onInit();
44  jsk_recognition_msgs::ClusterPointIndices>(
45  *pnh_, "output/indices", 1);
47  }
48 
50  {
51  sub_indices_ = pnh_->subscribe(
52  "input/indices", 10,
54  sub_cloud_ = pnh_->subscribe(
55  "input/cloud", 10,
57  }
58 
60  {
63  }
64 
66  const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
67  {
68  // ROS_INFO("PROCESSING CLOUD CALLBACK");
69 
70  // boost::mutex::scoped_lock lock(this->mutex_);
71  // vital_checker_->poke();
72  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
73  pcl::fromROSMsg(*cloud_msg, *cloud);
74  std::vector<pcl::PointCloud<PointT>::Ptr> cloud_clusters;
75  std::vector<pcl::PointCloud<pcl::Normal>::Ptr> normal_clusters;
76  pcl::PointCloud<pcl::PointXYZ>::Ptr centroids(
77  new pcl::PointCloud<pcl::PointXYZ>);
78  this->segmentCloud(
79  cloud, this->indices_, cloud_clusters, normal_clusters, centroids);
80  std::vector<std::vector<int> > neigbour_idx;
81  this->nearestNeigborSearch(centroids, neigbour_idx, 4);
84  rag->generateRAG(
85  cloud_clusters,
86  normal_clusters,
87  centroids,
88  neigbour_idx,
89  rag->RAG_EDGE_WEIGHT_CONVEX_CRITERIA);
90  rag->splitMergeRAG(0.0);
91  std::vector<int> labelMD;
92  rag->getCloudClusterLabels(labelMD);
93  std::map<int, pcl::PointIndices> _indices;
95  cloud_clusters, cloud, labelMD, _indices);
96  std::vector<pcl::PointIndices> all_indices;
97  for (std::map<int, pcl::PointIndices>::iterator it = _indices.begin();
98  it != _indices.end(); it++) {
99  all_indices.push_back((*it).second);
100  }
101 
102  // ROS_INFO("Size: %ld", _indices.size());
103 
104  jsk_recognition_msgs::ClusterPointIndices ros_indices;
105  ros_indices.cluster_indices = pcl_conversions::convertToROSPointIndices(
106  all_indices, cloud_msg->header);
107  ros_indices.header = cloud_msg->header;
108  pub_indices_.publish(ros_indices);
109  }
110 
112  const jsk_recognition_msgs::ClusterPointIndices &indices_msg)
113  {
114  // boost::mutex::scoped_lock lock(this->mutex_);
115  vital_checker_->poke();
116  this->indices_.clear();
117  std::vector<pcl_msgs::PointIndices> indices =
118  indices_msg.cluster_indices;
119  for (int i = 0; i < indices.size(); i++) {
120  pcl::PointIndices _index;
121  pcl_conversions::toPCL(indices[i], _index);
122  this->indices_.push_back(_index);
123  }
124  }
125 
127  const pcl::PointCloud<PointT>::Ptr cloud,
128  const std::vector<pcl::PointIndices> &indices,
129  std::vector<pcl::PointCloud<PointT>::Ptr> &cloud_clusters,
130  std::vector<pcl::PointCloud<pcl::Normal>::Ptr> &normal_clusters,
131  pcl::PointCloud<pcl::PointXYZ>::Ptr centroids)
132  {
133  boost::mutex::scoped_lock lock(this->mutex_);
134  pcl::ExtractIndices<PointT>::Ptr eifilter(
135  new pcl::ExtractIndices<PointT>);
136  eifilter->setInputCloud(cloud);
137  for (int i = 0; i < indices.size(); i++) {
138  pcl::PointIndices::Ptr index(new pcl::PointIndices());
139  index->indices = indices[i].indices;
140  eifilter->setIndices(index);
141  pcl::PointCloud<PointT>::Ptr tmp_cloud(
142  new pcl::PointCloud<PointT>);
143  eifilter->filter(*tmp_cloud);
144  if (tmp_cloud->width > 0) {
145  Eigen::Vector4f centroid;
146  pcl::compute3DCentroid<PointT, float>(*cloud, *index, centroid);
147  float ct_x = static_cast<float>(centroid[0]);
148  float ct_y = static_cast<float>(centroid[1]);
149  float ct_z = static_cast<float>(centroid[2]);
150  if (!std::isnan(ct_x) && !std::isnan(ct_y) && !std::isnan(ct_z)) {
151  pcl::PointCloud<pcl::Normal>::Ptr s_normal(
152  new pcl::PointCloud<pcl::Normal>);
154  tmp_cloud, s_normal, 40, 0.05, false);
155  normal_clusters.push_back(s_normal);
156  centroids->push_back(pcl::PointXYZ(ct_x, ct_y, ct_z));
157  cloud_clusters.push_back(tmp_cloud);
158  }
159  }
160  }
161  }
162 
164  const pcl::PointCloud<PointT>::Ptr cloud,
165  pcl::PointCloud<pcl::Normal>::Ptr s_normal,
166  const int k, const double radius, bool ksearch)
167  {
168  pcl::NormalEstimationOMP<PointT, pcl::Normal> ne;
169  ne.setInputCloud(cloud);
170  ne.setNumberOfThreads(8);
171  pcl::search::KdTree<PointT>::Ptr tree(
172  new pcl::search::KdTree<PointT> ());
173  ne.setSearchMethod(tree);
174  if (ksearch) {
175  ne.setKSearch(k);
176  } else {
177  ne.setRadiusSearch(radius);
178  }
179  ne.compute(*s_normal);
180  }
181 
183  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
184  std::vector<std::vector<int> > &pointIndices,
185  const int k, const double radius, bool isneigbour)
186  {
187  pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
188  kdtree.setInputCloud(cloud);
189  std::vector<std::vector<float> > pointSquaredDistance;
190  for (int i = 0; i < cloud->size(); i++) {
191  std::vector<int>pointIdx;
192  std::vector<float> pointSqDist;
193  pcl::PointXYZ searchPoint = cloud->points[i];
194  if (isneigbour) {
195  kdtree.nearestKSearch(searchPoint, k, pointIdx, pointSqDist);
196  } else {
197  kdtree.radiusSearch(searchPoint, radius, pointIdx, pointSqDist);
198  }
199  pointIndices.push_back(pointIdx);
200  pointSquaredDistance.push_back(pointSqDist);
201  pointIdx.clear();
202  pointSqDist.clear();
203  }
204  }
205 
207  const std::vector<pcl::PointCloud<PointT>::Ptr> &cloud_clusters,
208  pcl::PointCloud<PointT>::Ptr cloud,
209  const std::vector<int> &labelMD,
210  std::map<int, pcl::PointIndices> &all_indices)
211  {
212  int icounter = 0;
213  for (int i = 0; i < cloud_clusters.size(); i++) {
214  int _idx = labelMD.at(i);
215  pcl::PointIndices _ind;
216  for (int j = 0; j < cloud_clusters[i]->size(); j++) {
217  _ind.indices.push_back(icounter++);
218  }
219  std::map<int, pcl::PointIndices>::iterator
220  iter = all_indices.find(_idx);
221  if (iter == all_indices.end()) {
222  all_indices.insert(
223  std::map<int, pcl::PointIndices>::value_type(_idx, _ind));
224  } else {
225  pcl::PointIndices prev_ind = (*iter).second;
226  prev_ind.indices.insert(prev_ind.indices.end(),
227  _ind.indices.begin(),
228  _ind.indices.end());
229  (*iter).second = prev_ind;
230  }
231  }
232  }
233 } // namespace jsk_pcl_ros
234 
void segmentCloud(const pcl::PointCloud< PointT >::Ptr, const std::vector< pcl::PointIndices > &, std::vector< pcl::PointCloud< PointT >::Ptr > &, std::vector< pcl::PointCloud< pcl::Normal >::Ptr > &, pcl::PointCloud< pcl::PointXYZ >::Ptr)
void cloud_cb(const sensor_msgs::PointCloud2::ConstPtr &)
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
void getConvexLabelCloudIndices(const std::vector< pcl::PointCloud< PointT >::Ptr > &, pcl::PointCloud< PointT >::Ptr, const std::vector< int > &, std::map< int, pcl::PointIndices > &)
ros::Publisher advertise(ros::NodeHandle &nh, std::string topic, int queue_size)
std::vector< pcl::PointIndices > indices_
void toPCL(const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
unsigned int index
boost::shared_ptr< ros::NodeHandle > pnh_
void nearestNeigborSearch(pcl::PointCloud< pcl::PointXYZ >::Ptr, std::vector< std::vector< int > > &, const int=8, const double=0.02, bool=true)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ConvexConnectedVoxels, nodelet::Nodelet)
void indices_cb(const jsk_recognition_msgs::ClusterPointIndices &)
std::vector< PCLIndicesMsg > convertToROSPointIndices(const std::vector< pcl::PointIndices::Ptr > cluster_indices, const std_msgs::Header &header)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
void estimatePointCloudNormals(const pcl::PointCloud< PointT >::Ptr, pcl::PointCloud< pcl::Normal >::Ptr, const int=8, const double=0.02, bool=true)
cloud


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