euclidean_cluster_extraction_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ryohei Ueda and JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
38 
39 using namespace std;
40 using namespace pcl;
41 
42 namespace jsk_pcl_ros
43 {
44 
45  void EuclideanClustering::downsample_cloud(
46  const pcl::PointCloud<pcl::PointXYZ>::Ptr& original_cloud,
47  pcl::PointCloud<pcl::PointXYZ>::Ptr& sampled_cloud,
48  std::vector<std::vector<int> >& sampled_to_original_indices,
49  std::vector<int>& original_to_sampled_indices,
50  double leaf_size)
51  {
52  pcl::VoxelGrid<pcl::PointXYZ> voxel;
53  voxel.setLeafSize(leaf_size, leaf_size, leaf_size);
54  voxel.setSaveLeafLayout(true);
55  voxel.setInputCloud(original_cloud);
56  voxel.filter(*sampled_cloud);
57  sampled_to_original_indices.resize(original_cloud->points.size());
58  original_to_sampled_indices.resize(original_cloud->points.size());
59  std::fill(original_to_sampled_indices.begin(),
60  original_to_sampled_indices.end(),
61  -1);
62  std::fill(sampled_to_original_indices.begin(),
63  sampled_to_original_indices.end(),
64  std::vector<int>());
65  for (size_t i = 0; i < original_cloud->points.size(); ++i) {
66  pcl::PointXYZ p = original_cloud->points[i];
67  if (std::isnan(p.x) || std::isnan(p.y) || std::isnan(p.z)) {
68  continue;
69  }
70  // to avoid invalid access (or use * getGridCoordinates+getCentroidIndexAt) instead of getCentroidIndex.
71  const int index = voxel.getCentroidIndexAt(
72  voxel.getGridCoordinates(p.x, p.y, p.z));
73  if (index == -1) {
74  continue;
75  }
76  original_to_sampled_indices[i] = index;
77  sampled_to_original_indices[index].push_back(i);
78  }
79  }
80 
81  void EuclideanClustering::clusteringClusterIndices(
82  pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud,
83  std::vector<pcl::PointIndices::Ptr> &cluster_indices,
84  std::vector<pcl::PointIndices> &clustered_indices) {
85 
86  boost::mutex::scoped_lock lock(mutex_);
87 
88  clustered_indices.clear();
89 
90 
91  pcl::PointCloud<pcl::PointXYZ>::Ptr preprocessed_cloud(
92  new pcl::PointCloud<pcl::PointXYZ>);
93  if (downsample_) {
94  downsample_cloud(cloud,
95  preprocessed_cloud,
96  downsample_to_original_indices_,
97  original_to_downsample_indices_,
98  leaf_size_);
99 
100  } else {
101  preprocessed_cloud = cloud;
102  }
103 
104  if (preprocessed_cloud->points.size() == 0) {
105  return;
106  }
107 
108  for(pcl::PointIndices::Ptr point_indices : cluster_indices){
109  pcl::PointIndices::Ptr nonnan_indices (new pcl::PointIndices);
110  for(int original_index : point_indices->indices) {
111  int index;
112  if (downsample_) {
113  index = original_to_downsample_indices_[original_index];
114  } else {
115  index = original_index;
116  }
117  if (index == -1) {
118  continue;
119  }
120 
121  pcl::PointXYZ p = preprocessed_cloud->points[index];
122  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
123  nonnan_indices->indices.push_back(index);
124  }
125  }
126  removeDuplicatedIndices(nonnan_indices);
127 
128  pcl::PointIndices result_point_indices;
129  if (nonnan_indices->indices.size() > 0) {
130  // Create the filtering object
131  pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_cloud(new pcl::PointCloud<pcl::PointXYZ>);
132  {
133  pcl::ExtractIndices<pcl::PointXYZ> extract;
134  extract.setInputCloud(preprocessed_cloud);
135  extract.setIndices (nonnan_indices);
136  extract.setNegative(false);
137  extract.filter (*filtered_cloud);
138  }
139 
141  if (filtered_cloud->points.size() > 0) {
142  jsk_topic_tools::ScopedTimer timer = kdtree_acc_.scopedTimer();
143 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
144  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>());
145 #elif ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
146  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
147  tree = boost::make_shared< pcl::search::KdTree<pcl::PointXYZ> > ();
148 #else
149  pcl::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::KdTreeFLANN<pcl::PointXYZ>);
150  tree = boost::make_shared<pcl::KdTreeFLANN<pcl::PointXYZ> > ();
151 #endif
152  tree->setInputCloud(filtered_cloud);
153  impl.setClusterTolerance(tolerance);
154  impl.setMinClusterSize(minsize_);
155  impl.setMaxClusterSize(maxsize_);
156  impl.setSearchMethod(tree);
157  impl.setInputCloud(filtered_cloud);
158  }
159 
160  std::vector<pcl::PointIndices> output_indices;
161  {
162  jsk_topic_tools::ScopedTimer timer = segmentation_acc_.scopedTimer();
163  impl.extract(output_indices);
164  if (downsample_) {
165  for (size_t i = 0; i < output_indices.size(); ++i) {
166  pcl::PointIndices::Ptr tmp_indices(new pcl::PointIndices);
167  for (size_t j = 0; j < output_indices.at(i).indices.size(); ++j) {
168  tmp_indices->indices.insert(
169  tmp_indices->indices.end(),
170  downsample_to_original_indices_[nonnan_indices->indices[output_indices.at(i).indices[j]]].begin(),
171  downsample_to_original_indices_[nonnan_indices->indices[output_indices.at(i).indices[j]]].end());
172  }
173  removeDuplicatedIndices(tmp_indices);
174  output_indices[i] = *tmp_indices;
175  }
176  } else {
177  for (size_t i = 0; i < output_indices.size(); ++i) {
178  pcl::PointIndices tmp_indices;
179  tmp_indices.indices.resize( output_indices.at(i).indices.size());
180  for (size_t j = 0; j < output_indices.at(i).indices.size(); ++j) {
181  tmp_indices.indices[j] = nonnan_indices->indices[output_indices.at(i).indices[j]];
182  }
183  output_indices[i] = tmp_indices;
184  }
185  }
186  }
187  std::vector<int> result_indices;
188  std::vector<int> examine_indices;
189  switch (cluster_filter_type_) {
190  case jsk_pcl_ros::EuclideanClustering_All: {
191  for (size_t i_e = 0; i_e < output_indices.size(); ++i_e) {
192  examine_indices.push_back(i_e);
193  }
194  break;
195  }
196  case jsk_pcl_ros::EuclideanClustering_MaxSize: {
197  // take maximum size of cluster
198  int size = 0;
199  int index = -1;
200  for(size_t i=0; i < output_indices.size(); i++){
201  if(output_indices[i].indices.size() > size){
202  size = output_indices[i].indices.size();
203  index = i;
204  }
205  }
206  if (index >=0) {
207  examine_indices.push_back(index);
208  }
209  break;
210  }
211  }
212  for (int index : examine_indices) {
213  result_point_indices.indices = output_indices.at(index).indices;
214  clustered_indices.push_back(result_point_indices);
215  }
216  } else {
217  clustered_indices.push_back(result_point_indices);
218  }
219  }
220  }
221 
222  void EuclideanClustering::extract(
223  const sensor_msgs::PointCloud2ConstPtr &input)
224  {
225  vital_checker_->poke();
226  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
227  (new pcl::PointCloud<pcl::PointXYZ>);
229 
230  pcl::PointIndices::Ptr whole_indices(new pcl::PointIndices);
231  whole_indices->indices.resize(input->height * input->width);
232  for (size_t i = 0; i < input->height * input->width; ++i) {
233  whole_indices->indices[i] = i;
234  }
235  std::vector<pcl::PointIndices::Ptr> cluster_indices{whole_indices};
236  std::vector<pcl::PointIndices> clustered_indices;
237  clusteringClusterIndices(cloud,
238  cluster_indices,
239  clustered_indices);
240 
241  // Publish result indices
242  jsk_recognition_msgs::ClusterPointIndices result;
243  result.cluster_indices.resize(clustered_indices.size());
244  cluster_counter_.add(clustered_indices.size());
245  result.header = input->header;
246  if (cogs_.size() != 0 && cogs_.size() == clustered_indices.size()) {
247  // tracking the labels
248  //ROS_INFO("computing distance matrix");
249  // compute distance matrix
250  // D[i][j] --> distance between the i-th previous cluster
251  // and the current j-th cluster
252  Vector4fVector new_cogs;
253  computeCentroidsOfClusters(new_cogs, cloud, clustered_indices);
254  double D[cogs_.size() * new_cogs.size()];
255  computeDistanceMatrix(D, cogs_, new_cogs);
256  std::vector<int> pivot_table = buildLabelTrackingPivotTable(D, cogs_, new_cogs, label_tracking_tolerance);
257  if (pivot_table.size() != 0) {
258  clustered_indices = pivotClusterIndices(pivot_table, clustered_indices);
259  }
260  }
261  Vector4fVector tmp_cogs;
262  computeCentroidsOfClusters(tmp_cogs, cloud, clustered_indices); // NB: not efficient
263  cogs_ = tmp_cogs;
264 
265  for (size_t i = 0; i < clustered_indices.size(); i++) {
266 #if ROS_VERSION_MINIMUM(1, 10, 0)
267  // hydro and later
268  result.cluster_indices[i].header
269  = pcl_conversions::fromPCL(clustered_indices[i].header);
270 #else
271  // groovy
272  result.cluster_indices[i].header = clustered_indices[i].header;
273 #endif
274  result.cluster_indices[i].indices = clustered_indices[i].indices;
275  }
276 
277  result_pub_.publish(result);
278 
279  jsk_recognition_msgs::Int32Stamped::Ptr cluster_num_msg (new jsk_recognition_msgs::Int32Stamped);
280  cluster_num_msg->header = input->header;
281  cluster_num_msg->data = clustered_indices.size();
282  cluster_num_pub_.publish(cluster_num_msg);
283 
284  diagnostic_updater_->update();
285  }
286 
287  void EuclideanClustering::multi_extract(
288  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_cluster_indices,
289  const sensor_msgs::PointCloud2::ConstPtr& input) {
290  vital_checker_->poke();
291  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
292  (new pcl::PointCloud<pcl::PointXYZ>);
294 
295  std::vector<pcl::PointIndices::Ptr> cluster_indices =
296  pcl_conversions::convertToPCLPointIndices(input_cluster_indices->cluster_indices);
297  std::vector<pcl::PointIndices> clustered_indices;
298  clusteringClusterIndices(cloud,
299  cluster_indices,
300  clustered_indices);
301 
302  // Publish result indices
303  jsk_recognition_msgs::ClusterPointIndices result;
304  result.cluster_indices.resize(clustered_indices.size());
305  cluster_counter_.add(clustered_indices.size());
306  result.header = input->header;
307 
308  for (size_t i = 0; i < clustered_indices.size(); i++) {
309 #if ROS_VERSION_MINIMUM(1, 10, 0)
310  // hydro and later
311  result.cluster_indices[i].header
312  = pcl_conversions::fromPCL(clustered_indices[i].header);
313 #else
314  // groovy
315  result.cluster_indices[i].header = clustered_indices[i].header;
316 #endif
317  result.cluster_indices[i].indices = clustered_indices[i].indices;
318  }
319 
320  result_pub_.publish(result);
321 
322  jsk_recognition_msgs::Int32Stamped::Ptr cluster_num_msg (new jsk_recognition_msgs::Int32Stamped);
323  cluster_num_msg->header = input->header;
324  cluster_num_msg->data = clustered_indices.size();
325  cluster_num_pub_.publish(cluster_num_msg);
326 
327  diagnostic_updater_->update();
328  }
329 
330  bool EuclideanClustering::serviceCallback(
331  jsk_recognition_msgs::EuclideanSegment::Request &req,
332  jsk_recognition_msgs::EuclideanSegment::Response &res)
333  {
334  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
335  pcl::fromROSMsg(req.input, *cloud);
336 
337 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
338  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ> ());
339 #elif ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
340  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
341  tree = boost::make_shared< pcl::search::KdTree<pcl::PointXYZ> > ();
342 #else
343  pcl::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::KdTreeFLANN<pcl::PointXYZ>);
344  tree = boost::make_shared<pcl::KdTreeFLANN<pcl::PointXYZ> > ();
345 #endif
346 
347  vector<pcl::PointIndices> cluster_indices;
349  double tor;
350  if ( req.tolerance < 0) {
351  tor = tolerance;
352  } else {
353  tor = req.tolerance;
354  }
355  impl.setClusterTolerance (tor);
356  impl.setMinClusterSize (minsize_);
357  impl.setMaxClusterSize (maxsize_);
358  impl.setSearchMethod (tree);
359  impl.setInputCloud (cloud);
360  impl.extract (cluster_indices);
361 
362  res.output.resize( cluster_indices.size() );
363 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 7 )
364  pcl::PCLPointCloud2::Ptr pcl_cloud(new pcl::PCLPointCloud2);
365  pcl_conversions::toPCL(req.input, *pcl_cloud);
366  pcl::ExtractIndices<pcl::PCLPointCloud2> ex;
367  ex.setInputCloud(pcl_cloud);
368 #elif ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
369  pcl::ExtractIndices<sensor_msgs::PointCloud2> ex;
370  ex.setInputCloud ( req.input.makeShared() );
371 #else
372  pcl::ExtractIndices<sensor_msgs::PointCloud2> ex;
373  ex.setInputCloud ( boost::make_shared< sensor_msgs::PointCloud2 > (req.input) );
374 #endif
375  for ( size_t i = 0; i < cluster_indices.size(); i++ ) {
376 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
377  ex.setIndices ( std::make_shared< pcl::PointIndices > (cluster_indices[i]) );
378 #else
379  ex.setIndices ( boost::make_shared< pcl::PointIndices > (cluster_indices[i]) );
380 #endif
381  ex.setNegative ( false );
382 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 7 )
383  pcl::PCLPointCloud2 output_cloud;
384  ex.filter ( output_cloud );
385  pcl_conversions::fromPCL(output_cloud, res.output[i]);
386 #else
387  ex.filter ( res.output[i] );
388 #endif
389  }
390  return true;
391  }
392 
393  void EuclideanClustering::onInit()
394  {
395  DiagnosticNodelet::onInit();
396 
397  pnh_->param("multi", multi_, false);
398  pnh_->param("approximate_sync", approximate_sync_, false);
399  pnh_->param("queue_size", queue_size_, 20);
400 
402  // dynamic reconfigure
404  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
405  dynamic_reconfigure::Server<Config>::CallbackType f =
406  boost::bind (&EuclideanClustering::configCallback, this, _1, _2);
407  srv_->setCallback (f);
408 
410  // Publisher
412  result_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices> (*pnh_, "output", 1);
413  cluster_num_pub_ = advertise<jsk_recognition_msgs::Int32Stamped> (*pnh_, "cluster_num", 1);
414  service_ = pnh_->advertiseService(pnh_->resolveName("euclidean_clustering"),
415  &EuclideanClustering::serviceCallback, this);
416 
417  onInitPostProcess();
418  }
419 
420  EuclideanClustering::~EuclideanClustering() {
421  // message_filters::Synchronizer needs to be called reset
422  // before message_filters::Subscriber is freed.
423  // Calling reset fixes the following error on shutdown of the nodelet:
424  // terminate called after throwing an instance of
425  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
426  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
427  // Also see https://github.com/ros/ros_comm/issues/720 .
428  sync_.reset();
429  async_.reset();
430  }
431 
432  void EuclideanClustering::subscribe()
433  {
435  // Subscription
437  if (multi_) {
438  sub_cluster_indices_.subscribe(*pnh_, "input/cluster_indices", 1);
439  sub_point_cloud_.subscribe(*pnh_, "input", 1);
440  if (approximate_sync_) {
441  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
442  async_->connectInput(sub_cluster_indices_, sub_point_cloud_);
443  async_->registerCallback(boost::bind(&EuclideanClustering::multi_extract, this, _1, _2));
444  } else {
445  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
446  sync_->connectInput(sub_cluster_indices_, sub_point_cloud_);
447  sync_->registerCallback(boost::bind(&EuclideanClustering::multi_extract, this, _1, _2));
448  }
449  } else {
450  sub_input_ = pnh_->subscribe("input", 1, &EuclideanClustering::extract, this);
451  }
452  }
453 
454  void EuclideanClustering::unsubscribe()
455  {
456  if (multi_) {
457  sub_cluster_indices_.unsubscribe();
458  sub_point_cloud_.unsubscribe();
459  } else {
460  sub_input_.shutdown();
461  }
462  }
463 
464  void EuclideanClustering::updateDiagnostic(
466  {
467  if (vital_checker_->isAlive()) {
468  stat.summary(
469  diagnostic_msgs::DiagnosticStatus::OK,
470  "EuclideanSegmentation running");
471 
472  jsk_topic_tools::addDiagnosticInformation(
473  "Kdtree Construction", kdtree_acc_, stat);
474  jsk_topic_tools::addDiagnosticInformation(
475  "Euclidean Segmentation", segmentation_acc_, stat);
476  stat.add("Cluster Num (Avg.)", cluster_counter_.mean());
477  stat.add("Max Size of the cluster", maxsize_);
478  stat.add("Min Size of the cluster", minsize_);
479  stat.add("Cluster tolerance", tolerance);
480  stat.add("Tracking tolerance", label_tracking_tolerance);
481  stat.add("MultiEuclideanClustering", multi_);
482  stat.add("Downsample enable", downsample_);
483  if (downsample_) {
484  stat.add("Leaf size", leaf_size_);
485  }
486  }
487  DiagnosticNodelet::updateDiagnostic(stat);
488  }
489 
490  void EuclideanClustering::configCallback (Config &config, uint32_t level)
491  {
492  boost::mutex::scoped_lock lock(mutex_);
493  tolerance = config.tolerance;
494  label_tracking_tolerance = config.label_tracking_tolerance;
495  maxsize_ = config.max_size;
496  minsize_ = config.min_size;
497  cluster_filter_type_ = config.cluster_filter;
498  // downsample group
499  downsample_ = config.downsample_enable;
500  leaf_size_ = config.leaf_size;
501  }
502 
503  std::vector<pcl::PointIndices> EuclideanClustering::pivotClusterIndices(
504  std::vector<int>& pivot_table,
505  std::vector<pcl::PointIndices>& cluster_indices)
506  {
507  std::vector<pcl::PointIndices> new_cluster_indices;
508  new_cluster_indices.resize(pivot_table.size());
509  for (size_t i = 0; i < pivot_table.size(); i++) {
510  new_cluster_indices[i] = cluster_indices[pivot_table[i]];
511  }
512  return new_cluster_indices;
513  }
514  std::vector<int> EuclideanClustering::buildLabelTrackingPivotTable(
515  double* D, Vector4fVector cogs, Vector4fVector new_cogs,
516  double label_tracking_tolerance)
517  {
518  std::vector<int> pivot_table;
519  // initialize pivot table
520  pivot_table.resize(cogs.size());
521  for (size_t i = 0; i < pivot_table.size(); i++)
522  pivot_table[i] = i;
523  for (size_t pivot_counter = 0; pivot_counter < pivot_table.size();
524  pivot_counter++)
525  {
526  double minimum_distance = DBL_MAX;
527  size_t minimum_previous_index = 0;
528  size_t minimum_next_index = 0;
529  for (size_t i = 0; i < cogs.size(); i++)
530  {
531  for (size_t j = 0; j < new_cogs.size(); j++)
532  {
533  double distance = D[i * cogs.size() + j];
534  //ROS_INFO("distance %lux%lu: %f", i, j, distance);
535  if (distance < minimum_distance)
536  {
537  minimum_distance = distance;
538  minimum_previous_index = i;
539  minimum_next_index = j;
540  }
541  }
542  }
543  if (minimum_distance > label_tracking_tolerance)
544  {
545  // ROS_WARN("minimum tracking distance exceeds tolerance: %f > %f",
546  // minimum_distance, label_tracking_tolerance);
547  std::vector<int> dummy;
548  return dummy;
549  }
550  pivot_table[minimum_previous_index] = minimum_next_index;
551  // fill the D matrix with DBL_MAX
552  for (size_t j = 0; j < new_cogs.size(); j++)
553  {
554  D[minimum_previous_index * cogs.size() + j] = DBL_MAX;
555  }
556  }
557  return pivot_table;
558  }
559 
560  void EuclideanClustering::computeDistanceMatrix(
561  double* D,
562  Vector4fVector& old_cogs,
563  Vector4fVector& new_cogs)
564  {
565  for (size_t i = 0; i < old_cogs.size(); i++) {
566  Eigen::Vector4f previous_cog = old_cogs[i];
567  for (size_t j = 0; j < new_cogs.size(); j++) {
568  Eigen::Vector4f next_cog = new_cogs[j];
569  double distance = (next_cog - previous_cog).norm();
570  D[i * old_cogs.size() + j] = distance;
571  }
572  }
573  }
574 
575  void EuclideanClustering::removeDuplicatedIndices(
576  pcl::PointIndices::Ptr indices)
577  {
578  std::sort(indices->indices.begin(), indices->indices.end());
579  indices->indices.erase(
580  std::unique(indices->indices.begin(), indices->indices.end()),
581  indices->indices.end());
582  }
583 
584  void EuclideanClustering::computeCentroidsOfClusters(
585  Vector4fVector& ret,
586  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
587  std::vector<pcl::PointIndices> cluster_indices)
588  {
589  pcl::ExtractIndices<pcl::PointXYZ> extract;
590  extract.setInputCloud(cloud);
591  ret.resize(cluster_indices.size());
592  for (size_t i = 0; i < cluster_indices.size(); i++)
593  {
594  // build pointcloud
595  pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud (new pcl::PointCloud<pcl::PointXYZ>);
596  pcl::PointIndices::Ptr segmented_indices (new pcl::PointIndices);
597  for (size_t j = 0; j < cluster_indices[i].indices.size(); j++)
598  {
599  segmented_indices->indices.push_back(cluster_indices[i].indices[j]);
600  }
601  extract.setIndices(segmented_indices);
602  extract.filter(*segmented_cloud);
603  Eigen::Vector4f center;
604  pcl::compute3DCentroid(*segmented_cloud, center);
605  ret[i] = center;
606  }
607  }
608 
609 }
610 
613 
pcl_ros::EuclideanClusterExtraction
extract_top_polygon_likelihood.ex
ex
Definition: extract_top_polygon_likelihood.py:51
result
def result
pcl
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
_2
boost::arg< 2 > _2
i
int i
diagnostic_updater::DiagnosticStatusWrapper::add
void add(const std::string &key, const bool &b)
jsk_pcl_ros::EuclideanClustering::Vector4fVector
std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > Vector4fVector
Definition: euclidean_cluster_extraction_nodelet.h:149
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
p
p
euclidean_cluster_extraction_nodelet.h
pcl_conversions::toPCL
void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
pcl_conversions::convertToPCLPointIndices
std::vector< pcl::PointIndices::Ptr > convertToPCLPointIndices(const std::vector< PCLIndicesMsg > &cluster_indices)
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
cloud
cloud
mutex_
boost::mutex mutex_
class_list_macros.h
jsk_pcl_ros::EuclideanClustering::Config
jsk_pcl_ros::EuclideanClusteringConfig Config
Definition: euclidean_cluster_extraction_nodelet.h:146
tree
tree
diagnostic_updater::DiagnosticStatusWrapper::summary
void summary(const diagnostic_msgs::DiagnosticStatus &src)
pcl_conversions::fromPCL
void fromPCL(const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
jsk_pcl_ros
Definition: add_color_from_image.h:51
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::EuclideanClustering, nodelet::Nodelet)
_1
boost::arg< 1 > _1
jsk_pcl_ros::EuclideanClustering
Definition: euclidean_cluster_extraction_nodelet.h:103
distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
nodelet::Nodelet
std
pcl_util.h
dump_depth_error.f
f
Definition: dump_depth_error.py:39
index
unsigned int index
tolerance
S tolerance()
diagnostic_updater::DiagnosticStatusWrapper
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
config
config
D
D
size
size
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44