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/or 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>
65 #include <jsk_topic_tools/time_accumulator.h>
66 
67 #include <jsk_topic_tools/diagnostic_nodelet.h>
68 
69 namespace jsk_pcl_ros
70 {
71  class EuclideanClustering : public jsk_topic_tools::DiagnosticNodelet
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  virtual ~EuclideanClustering();
88  protected:
91 
92  void configCallback (Config &config, uint32_t level);
96 
99 
102 
104 
105  double tolerance;
107  int minsize_;
108  int maxsize_;
109  bool downsample_;
110  double leaf_size_;
111  bool multi_;
112  bool approximate_sync_;
113  int queue_size_;
115 
116  std::vector<std::vector<int> > downsample_to_original_indices_;
117  std::vector<int> original_to_downsample_indices_;
118 
119  jsk_topic_tools::TimeAccumulator segmentation_acc_;
120  jsk_topic_tools::TimeAccumulator kdtree_acc_;
122 
123  // the list of COGs of each cluster
125 
126  virtual void onInit();
127  virtual void extract(const sensor_msgs::PointCloud2ConstPtr &input);
128  virtual void multi_extract(const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cluster_indices,
129  const sensor_msgs::PointCloud2::ConstPtr& input);
130  virtual void clusteringClusterIndices(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud,
131  std::vector<pcl::PointIndices::Ptr> &cluster_indices,
132  std::vector<pcl::PointIndices> &clustered_indices);
133  bool serviceCallback(jsk_recognition_msgs::EuclideanSegment::Request &req,
134  jsk_recognition_msgs::EuclideanSegment::Response &res);
136  virtual std::vector<pcl::PointIndices> pivotClusterIndices(
137  std::vector<int>& pivot_table,
138  std::vector<pcl::PointIndices>& cluster_indices);
139 
140  virtual std::vector<int> buildLabelTrackingPivotTable(
141  double* D,
142  Vector4fVector cogs,
143  Vector4fVector new_cogs,
145 
146  virtual void computeDistanceMatrix(
147  double* D,
148  Vector4fVector& old_cogs,
149  Vector4fVector& new_cogs);
150 
151  virtual void
153  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
154  std::vector<pcl::PointIndices> cluster_indices);
155  virtual void removeDuplicatedIndices(pcl::PointIndices::Ptr indices);
156 
158  const pcl::PointCloud<pcl::PointXYZ>::Ptr& original_cloud,
159  pcl::PointCloud<pcl::PointXYZ>::Ptr& sampled_cloud,
160  std::vector<std::vector<int> >& sampled_to_original_indices,
161  std::vector<int>& original_to_sampled_indices,
162  double leaf_size);
163 
164  virtual void subscribe();
165  virtual void unsubscribe();
166  };
167 
168 }
169 
170 #endif
jsk_pcl_ros::EuclideanClustering::cogs_
Vector4fVector cogs_
Definition: euclidean_cluster_extraction_nodelet.h:188
jsk_pcl_ros::EuclideanClustering::sub_point_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_point_cloud_
Definition: euclidean_cluster_extraction_nodelet.h:165
jsk_pcl_ros::EuclideanClustering::cluster_filter_type_
int cluster_filter_type_
Definition: euclidean_cluster_extraction_nodelet.h:178
jsk_pcl_ros::EuclideanClustering::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: euclidean_cluster_extraction_nodelet.h:162
jsk_pcl_ros::EuclideanClustering::approximate_sync_
bool approximate_sync_
Definition: euclidean_cluster_extraction_nodelet.h:176
ros::Publisher
jsk_pcl_ros::EuclideanClustering::serviceCallback
bool serviceCallback(jsk_recognition_msgs::EuclideanSegment::Request &req, jsk_recognition_msgs::EuclideanSegment::Response &res)
Definition: euclidean_cluster_extraction_nodelet.cpp:330
boost::shared_ptr
jsk_pcl_ros::EuclideanClustering::Vector4fVector
std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > Vector4fVector
Definition: euclidean_cluster_extraction_nodelet.h:149
ros.h
jsk_pcl_ros::EuclideanClustering::leaf_size_
double leaf_size_
Definition: euclidean_cluster_extraction_nodelet.h:174
jsk_pcl_ros::EuclideanClustering::sub_cluster_indices_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_cluster_indices_
Definition: euclidean_cluster_extraction_nodelet.h:164
jsk_pcl_ros::EuclideanClustering::ApproximateSyncPolicy
message_filters::sync_policies::ApproximateTime< jsk_recognition_msgs::ClusterPointIndices, sensor_msgs::PointCloud2 > ApproximateSyncPolicy
Definition: euclidean_cluster_extraction_nodelet.h:144
jsk_pcl_ros::EuclideanClustering::buildLabelTrackingPivotTable
virtual std::vector< int > buildLabelTrackingPivotTable(double *D, Vector4fVector cogs, Vector4fVector new_cogs, double label_tracking_tolerance)
Definition: euclidean_cluster_extraction_nodelet.cpp:514
jsk_pcl_ros::EuclideanClustering::kdtree_acc_
jsk_topic_tools::TimeAccumulator kdtree_acc_
Definition: euclidean_cluster_extraction_nodelet.h:184
jsk_pcl_ros::EuclideanClustering::computeCentroidsOfClusters
virtual void computeCentroidsOfClusters(Vector4fVector &ret, pcl::PointCloud< pcl::PointXYZ >::Ptr cloud, std::vector< pcl::PointIndices > cluster_indices)
Definition: euclidean_cluster_extraction_nodelet.cpp:584
jsk_pcl_ros::EuclideanClustering::EuclideanClustering
EuclideanClustering()
Definition: euclidean_cluster_extraction_nodelet.h:150
jsk_pcl_ros::EuclideanClustering::queue_size_
int queue_size_
Definition: euclidean_cluster_extraction_nodelet.h:177
jsk_pcl_ros::EuclideanClustering::clusteringClusterIndices
virtual void clusteringClusterIndices(pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, std::vector< pcl::PointIndices::Ptr > &cluster_indices, std::vector< pcl::PointIndices > &clustered_indices)
Definition: euclidean_cluster_extraction_nodelet.cpp:81
jsk_pcl_ros::EuclideanClustering::removeDuplicatedIndices
virtual void removeDuplicatedIndices(pcl::PointIndices::Ptr indices)
Definition: euclidean_cluster_extraction_nodelet.cpp:575
jsk_pcl_ros::EuclideanClustering::original_to_downsample_indices_
std::vector< int > original_to_downsample_indices_
Definition: euclidean_cluster_extraction_nodelet.h:181
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices >
ros::ServiceServer
jsk_pcl_ros::EuclideanClustering::pivotClusterIndices
virtual std::vector< pcl::PointIndices > pivotClusterIndices(std::vector< int > &pivot_table, std::vector< pcl::PointIndices > &cluster_indices)
Definition: euclidean_cluster_extraction_nodelet.cpp:503
pcl_nodelet.h
jsk_pcl_ros::EuclideanClustering::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: euclidean_cluster_extraction_nodelet.h:153
jsk_pcl_ros::EuclideanClustering::Config
jsk_pcl_ros::EuclideanClusteringConfig Config
Definition: euclidean_cluster_extraction_nodelet.h:146
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros::EuclideanClustering::sub_input_
ros::Subscriber sub_input_
Definition: euclidean_cluster_extraction_nodelet.h:158
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::EuclideanClustering::minsize_
int minsize_
Definition: euclidean_cluster_extraction_nodelet.h:171
jsk_pcl_ros::EuclideanClustering::SyncPolicy
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::ClusterPointIndices, sensor_msgs::PointCloud2 > SyncPolicy
Definition: euclidean_cluster_extraction_nodelet.h:140
jsk_pcl_ros::EuclideanClustering::downsample_
bool downsample_
Definition: euclidean_cluster_extraction_nodelet.h:173
jsk_pcl_ros::EuclideanClustering::extract
virtual void extract(const sensor_msgs::PointCloud2ConstPtr &input)
Definition: euclidean_cluster_extraction_nodelet.cpp:222
jsk_pcl_ros::EuclideanClustering::computeDistanceMatrix
virtual void computeDistanceMatrix(double *D, Vector4fVector &old_cogs, Vector4fVector &new_cogs)
Definition: euclidean_cluster_extraction_nodelet.cpp:560
jsk_pcl_ros::EuclideanClustering::maxsize_
int maxsize_
Definition: euclidean_cluster_extraction_nodelet.h:172
jsk_pcl_ros::EuclideanClustering::cluster_counter_
jsk_recognition_utils::Counter cluster_counter_
Definition: euclidean_cluster_extraction_nodelet.h:185
jsk_pcl_ros::EuclideanClustering::subscribe
virtual void subscribe()
Definition: euclidean_cluster_extraction_nodelet.cpp:432
pcl_conversion_util.h
jsk_pcl_ros::EuclideanClustering::multi_
bool multi_
Definition: euclidean_cluster_extraction_nodelet.h:175
jsk_pcl_ros::EuclideanClustering::downsample_to_original_indices_
std::vector< std::vector< int > > downsample_to_original_indices_
Definition: euclidean_cluster_extraction_nodelet.h:180
jsk_pcl_ros::EuclideanClustering::label_tracking_tolerance
double label_tracking_tolerance
Definition: euclidean_cluster_extraction_nodelet.h:170
jsk_pcl_ros::EuclideanClustering::updateDiagnostic
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: euclidean_cluster_extraction_nodelet.cpp:464
jsk_pcl_ros::EuclideanClustering::segmentation_acc_
jsk_topic_tools::TimeAccumulator segmentation_acc_
Definition: euclidean_cluster_extraction_nodelet.h:183
jsk_recognition_utils::Counter
jsk_pcl_ros::EuclideanClustering::mutex_
boost::mutex mutex_
Definition: euclidean_cluster_extraction_nodelet.h:154
names.h
jsk_pcl_ros::EuclideanClustering::tolerance
double tolerance
Definition: euclidean_cluster_extraction_nodelet.h:169
jsk_pcl_ros::EuclideanClustering::multi_extract
virtual void multi_extract(const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &cluster_indices, const sensor_msgs::PointCloud2::ConstPtr &input)
Definition: euclidean_cluster_extraction_nodelet.cpp:287
jsk_pcl_ros::EuclideanClustering::configCallback
void configCallback(Config &config, uint32_t level)
Definition: euclidean_cluster_extraction_nodelet.cpp:490
pcl_util.h
jsk_pcl_ros::EuclideanClustering::cluster_num_pub_
ros::Publisher cluster_num_pub_
Definition: euclidean_cluster_extraction_nodelet.h:159
diagnostic_updater::DiagnosticStatusWrapper
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::EuclideanClustering::unsubscribe
virtual void unsubscribe()
Definition: euclidean_cluster_extraction_nodelet.cpp:454
jsk_pcl_ros::EuclideanClustering::downsample_cloud
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)
Definition: euclidean_cluster_extraction_nodelet.cpp:45
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
message_filters::sync_policies::ExactTime
jsk_pcl_ros::EuclideanClustering::result_pub_
ros::Publisher result_pub_
Definition: euclidean_cluster_extraction_nodelet.h:157
jsk_pcl_ros::EuclideanClustering::onInit
virtual void onInit()
Definition: euclidean_cluster_extraction_nodelet.cpp:393
jsk_pcl_ros::EuclideanClustering::~EuclideanClustering
virtual ~EuclideanClustering()
Definition: euclidean_cluster_extraction_nodelet.cpp:420
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
jsk_pcl_ros::EuclideanClustering::service_
ros::ServiceServer service_
Definition: euclidean_cluster_extraction_nodelet.h:167
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
ros::Subscriber
jsk_pcl_ros::EuclideanClustering::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: euclidean_cluster_extraction_nodelet.h:161


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