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/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 #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);
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_,
77  super.setInputCloud(cloud);
78  super.setColorImportance(color_importance_);
79  super.setSpatialImportance(spatial_importance_);
80  super.setNormalImportance(normal_importance_);
81  std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr > supervoxel_clusters;
82  super.extract(supervoxel_clusters);
83  pcl::PointCloud<PointT>::Ptr output (new pcl::PointCloud<PointT>);
84  std::vector<pcl::PointIndices> all_indices;
85  for (std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr >::iterator
86  it = supervoxel_clusters.begin();
87  it != supervoxel_clusters.end();
88  ++it) {
89  pcl::Supervoxel<PointT>::Ptr super_voxel = it->second;
90  pcl::PointCloud<PointT>::Ptr super_voxel_cloud = super_voxel->voxels_;
91  pcl::PointIndices indices;
92  // add indices...
93  for (size_t i = 0; i < super_voxel_cloud->size(); i++) {
94  indices.indices.push_back(i + output->points.size());
95  }
96  all_indices.push_back(indices);
97  *output = *output + *super_voxel_cloud; // append
98  }
99  sensor_msgs::PointCloud2 ros_cloud;
100  pcl::toROSMsg(*output, ros_cloud);
101  ros_cloud.header = cloud_msg->header;
102  jsk_recognition_msgs::ClusterPointIndices ros_indices;
103  ros_indices.cluster_indices = pcl_conversions::convertToROSPointIndices(
104  all_indices,
105  cloud_msg->header);
106  ros_indices.header = cloud_msg->header;
107  pub_cloud_.publish(ros_cloud);
108  pub_indices_.publish(ros_indices);
109  }
110  }
111 
112  void SupervoxelSegmentation::configCallback (Config &config, uint32_t level)
113  {
114  boost::mutex::scoped_lock lock(mutex_);
115  color_importance_ = config.color_importance;
116  spatial_importance_ = config.spatial_importance;
117  normal_importance_ = config.normal_importance;
118  voxel_resolution_ = config.voxel_resolution;
119  seed_resolution_ = config.seed_resolution;
120  use_transform_ = config.use_transform;
121  }
122 }
123 
124 
virtual void configCallback(Config &config, uint32_t level)
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::SupervoxelSegmentation, nodelet::Nodelet)
void output(int index, double value)
boost::shared_ptr< ros::NodeHandle > pnh_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
std::vector< PCLIndicesMsg > convertToROSPointIndices(const std::vector< pcl::PointIndices::Ptr > cluster_indices, const std_msgs::Header &header)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
cloud
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)


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