supervoxel_segmentation_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/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 #define BOOST_PARAMETER_MAX_ARITY 7
38 #include <pcl/segmentation/supervoxel_clustering.h>
39 namespace jsk_pcl_ros
40 {
42  {
43  DiagnosticNodelet::onInit();
44  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
45  dynamic_reconfigure::Server<Config>::CallbackType f =
46  boost::bind (
48  srv_->setCallback (f);
49  pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
50  *pnh_, "output/indices", 1);
51  pub_cloud_ = advertise<sensor_msgs::PointCloud2>(
52  *pnh_, "output/cloud", 1);
53  onInitPostProcess();
54  }
55 
57  {
58  sub_ = pnh_->subscribe("input", 1, &SupervoxelSegmentation::segment, this);
59  }
60 
62  {
63  sub_.shutdown();
64  }
65 
67  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
68  {
69  boost::mutex::scoped_lock lock(mutex_);
70  vital_checker_->poke();
71  if (cloud_msg->data.size() > 0) {
72  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
73  pcl::fromROSMsg(*cloud_msg, *cloud);
74  pcl::SupervoxelClustering<PointT> super(voxel_resolution_,
76 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
77  );
78 #else
79  , use_transform_);
80 #endif
81  super.setInputCloud(cloud);
82  super.setColorImportance(color_importance_);
83  super.setSpatialImportance(spatial_importance_);
84  super.setNormalImportance(normal_importance_);
85  std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr > supervoxel_clusters;
86  super.extract(supervoxel_clusters);
87  pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
88  std::vector<pcl::PointIndices> all_indices;
89  for (std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr >::iterator
90  it = supervoxel_clusters.begin();
91  it != supervoxel_clusters.end();
92  ++it) {
93  pcl::Supervoxel<PointT>::Ptr super_voxel = it->second;
94  pcl::PointCloud<PointT>::Ptr super_voxel_cloud = super_voxel->voxels_;
95  pcl::PointIndices indices;
96  // add indices...
97  for (size_t i = 0; i < super_voxel_cloud->size(); i++) {
98  indices.indices.push_back(i + output->points.size());
99  }
100  all_indices.push_back(indices);
101  *output = *output + *super_voxel_cloud; // append
102  }
103  sensor_msgs::PointCloud2 ros_cloud;
104  pcl::toROSMsg(*output, ros_cloud);
105  ros_cloud.header = cloud_msg->header;
106  jsk_recognition_msgs::ClusterPointIndices ros_indices;
107  ros_indices.cluster_indices = pcl_conversions::convertToROSPointIndices(
108  all_indices,
109  cloud_msg->header);
110  ros_indices.header = cloud_msg->header;
111  pub_cloud_.publish(ros_cloud);
112  pub_indices_.publish(ros_indices);
113  }
114  }
115 
116  void SupervoxelSegmentation::configCallback (Config &config, uint32_t level)
117  {
118  boost::mutex::scoped_lock lock(mutex_);
119  color_importance_ = config.color_importance;
120  spatial_importance_ = config.spatial_importance;
121  normal_importance_ = config.normal_importance;
122  voxel_resolution_ = config.voxel_resolution;
123  seed_resolution_ = config.seed_resolution;
124  use_transform_ = config.use_transform;
125  }
126 }
127 
128 
jsk_pcl_ros::SupervoxelSegmentation::Config
SupervoxelSegmentationConfig Config
Definition: supervoxel_segmentation.h:116
jsk_pcl_ros::SupervoxelSegmentation::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: supervoxel_segmentation.h:133
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
_2
boost::arg< 2 > _2
jsk_pcl_ros::SupervoxelSegmentation
Definition: supervoxel_segmentation.h:79
i
int i
jsk_pcl_ros::SupervoxelSegmentation::sub_
ros::Subscriber sub_
Definition: supervoxel_segmentation.h:132
jsk_pcl_ros::SupervoxelSegmentation::segment
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
Definition: supervoxel_segmentation_nodelet.cpp:66
jsk_pcl_ros::SupervoxelSegmentation::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: supervoxel_segmentation_nodelet.cpp:116
ros::Subscriber::shutdown
void shutdown()
jsk_pcl_ros::SupervoxelSegmentation::onInit
virtual void onInit()
Definition: supervoxel_segmentation_nodelet.cpp:41
jsk_pcl_ros::SupervoxelSegmentation::color_importance_
double color_importance_
Definition: supervoxel_segmentation.h:140
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
jsk_pcl_ros::SupervoxelSegmentation::seed_resolution_
double seed_resolution_
Definition: supervoxel_segmentation.h:144
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
cloud
cloud
class_list_macros.h
supervoxel_segmentation.h
jsk_pcl_ros::SupervoxelSegmentation::use_transform_
bool use_transform_
Definition: supervoxel_segmentation.h:145
jsk_pcl_ros::SupervoxelSegmentation::pub_cloud_
ros::Publisher pub_cloud_
Definition: supervoxel_segmentation.h:135
jsk_pcl_ros::SupervoxelSegmentation::spatial_importance_
double spatial_importance_
Definition: supervoxel_segmentation.h:141
jsk_pcl_ros
Definition: add_color_from_image.h:51
_1
boost::arg< 1 > _1
jsk_pcl_ros::SupervoxelSegmentation::normal_importance_
double normal_importance_
Definition: supervoxel_segmentation.h:142
jsk_pcl_ros::SupervoxelSegmentation::unsubscribe
virtual void unsubscribe()
Definition: supervoxel_segmentation_nodelet.cpp:61
nodelet::Nodelet
dump_depth_error.f
f
Definition: dump_depth_error.py:39
jsk_pcl_ros::SupervoxelSegmentation::pub_indices_
ros::Publisher pub_indices_
Definition: supervoxel_segmentation.h:134
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::SupervoxelSegmentation, nodelet::Nodelet)
pcl_conversions::convertToROSPointIndices
std::vector< PCLIndicesMsg > convertToROSPointIndices(const std::vector< pcl::PointIndices > cluster_indices, const std_msgs::Header &header)
config
config
jsk_pcl_ros::SupervoxelSegmentation::subscribe
virtual void subscribe()
Definition: supervoxel_segmentation_nodelet.cpp:56
jsk_pcl_ros::SupervoxelSegmentation::voxel_resolution_
double voxel_resolution_
Definition: supervoxel_segmentation.h:143
jsk_pcl_ros::SupervoxelSegmentation::mutex_
boost::mutex mutex_
Definition: supervoxel_segmentation.h:131


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