euclidean_cluster_extraction_nodelet.h
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 
36 #ifndef JSK_PCL_ROS_EUCLIDEAN_CLUSTER_EXTRACTION_NODELET_H_
37 #define JSK_PCL_ROS_EUCLIDEAN_CLUSTER_EXTRACTION_NODELET_H_
38 
39 #include <ros/ros.h>
40 #include <ros/names.h>
41 
42 #include <std_msgs/ColorRGBA.h>
43 
44 #include <dynamic_reconfigure/server.h>
45 
46 #include <pcl_ros/pcl_nodelet.h>
47 
48 #include <pcl/point_types.h>
49 #include <pcl/impl/point_types.hpp>
50 #include <pcl/kdtree/kdtree_flann.h>
51 #include <pcl/segmentation/sac_segmentation.h>
52 #include <pcl/segmentation/extract_clusters.h>
53 #include <pcl/filters/extract_indices.h>
54 #include <pcl/filters/voxel_grid.h>
55 #include <pcl/common/centroid.h>
56 
57 #include "jsk_recognition_msgs/ClusterPointIndices.h"
58 #include "jsk_recognition_msgs/EuclideanSegment.h"
59 #include "jsk_recognition_msgs/Int32Stamped.h"
60 
61 #include "jsk_pcl_ros/EuclideanClusteringConfig.h"
62 #include <Eigen/StdVector>
66 
68 
69 namespace jsk_pcl_ros
70 {
72  {
73  public:
75  jsk_recognition_msgs::ClusterPointIndices,
76  sensor_msgs::PointCloud2> SyncPolicy;
77 
79  jsk_recognition_msgs::ClusterPointIndices,
80  sensor_msgs::PointCloud2> ApproximateSyncPolicy;
81 
82  typedef jsk_pcl_ros::EuclideanClusteringConfig Config;
83  typedef std::vector<Eigen::Vector4f,
84  Eigen::aligned_allocator<Eigen::Vector4f> >
86  EuclideanClustering() : DiagnosticNodelet("EuclideanClustering") {}
87  protected:
90 
91  void configCallback (Config &config, uint32_t level);
95 
98 
101 
103 
104  double tolerance;
106  int minsize_;
107  int maxsize_;
109  double leaf_size_;
110  bool multi_;
114 
115  std::vector<std::vector<int> > downsample_to_original_indices_;
117 
121 
122  // the list of COGs of each cluster
124 
125  virtual void onInit();
126  virtual void extract(const sensor_msgs::PointCloud2ConstPtr &input);
127  virtual void multi_extract(const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cluster_indices,
128  const sensor_msgs::PointCloud2::ConstPtr& input);
129  virtual void clusteringClusterIndices(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud,
130  std::vector<pcl::PointIndices::Ptr> &cluster_indices,
131  std::vector<pcl::PointIndices> &clustered_indices);
132  bool serviceCallback(jsk_recognition_msgs::EuclideanSegment::Request &req,
133  jsk_recognition_msgs::EuclideanSegment::Response &res);
135  virtual std::vector<pcl::PointIndices> pivotClusterIndices(
136  std::vector<int>& pivot_table,
137  std::vector<pcl::PointIndices>& cluster_indices);
138 
139  virtual std::vector<int> buildLabelTrackingPivotTable(
140  double* D,
141  Vector4fVector cogs,
142  Vector4fVector new_cogs,
143  double label_tracking_tolerance);
144 
145  virtual void computeDistanceMatrix(
146  double* D,
147  Vector4fVector& old_cogs,
148  Vector4fVector& new_cogs);
149 
150  virtual void
152  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
153  std::vector<pcl::PointIndices> cluster_indices);
154  virtual void removeDuplicatedIndices(pcl::PointIndices::Ptr indices);
155 
156  void downsample_cloud(
157  const pcl::PointCloud<pcl::PointXYZ>::Ptr& original_cloud,
158  pcl::PointCloud<pcl::PointXYZ>::Ptr& sampled_cloud,
159  std::vector<std::vector<int> >& sampled_to_original_indices,
160  std::vector<int>& original_to_sampled_indices,
161  double leaf_size);
162 
163  virtual void subscribe();
164  virtual void unsubscribe();
165  };
166 
167 }
168 
169 #endif
void downsample_cloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &original_cloud, pcl::PointCloud< pcl::PointXYZ >::Ptr &sampled_cloud, std::vector< std::vector< int > > &sampled_to_original_indices, std::vector< int > &original_to_sampled_indices, double leaf_size)
virtual void computeCentroidsOfClusters(Vector4fVector &ret, pcl::PointCloud< pcl::PointXYZ >::Ptr cloud, std::vector< pcl::PointIndices > cluster_indices)
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
jsk_topic_tools::TimeAccumulator segmentation_acc_
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
std::vector< std::vector< int > > downsample_to_original_indices_
virtual void computeDistanceMatrix(double *D, Vector4fVector &old_cogs, Vector4fVector &new_cogs)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_cluster_indices_
virtual std::vector< pcl::PointIndices > pivotClusterIndices(std::vector< int > &pivot_table, std::vector< pcl::PointIndices > &cluster_indices)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void configCallback(Config &config, uint32_t level)
DiagnosticNodelet(const std::string &name)
virtual std::vector< int > buildLabelTrackingPivotTable(double *D, Vector4fVector cogs, Vector4fVector new_cogs, double label_tracking_tolerance)
message_filters::sync_policies::ApproximateTime< jsk_recognition_msgs::ClusterPointIndices, sensor_msgs::PointCloud2 > ApproximateSyncPolicy
virtual void clusteringClusterIndices(pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, std::vector< pcl::PointIndices::Ptr > &cluster_indices, std::vector< pcl::PointIndices > &clustered_indices)
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::ClusterPointIndices, sensor_msgs::PointCloud2 > SyncPolicy
boost::mutex mutex
global mutex.
jsk_pcl_ros::EuclideanClusteringConfig Config
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_point_cloud_
virtual void multi_extract(const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &cluster_indices, const sensor_msgs::PointCloud2::ConstPtr &input)
virtual void extract(const sensor_msgs::PointCloud2ConstPtr &input)
virtual void removeDuplicatedIndices(pcl::PointIndices::Ptr indices)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
bool serviceCallback(jsk_recognition_msgs::EuclideanSegment::Request &req, jsk_recognition_msgs::EuclideanSegment::Response &res)
std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > Vector4fVector


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