color_histogram_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2017, 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  * color_histogram_nodelet.cpp
37  * Author: Yuki Furuta <furushchev@jsk.imi.i.u-tokyo.ac.jp>
38  */
39 
41 #include <pcl/filters/extract_indices.h>
42 
43 #include <pcl/pcl_config.h>
44 #if PCL_VERSION_COMPARE (<, 1, 7, 2)
46 #else
48 #endif
49 
50 namespace jsk_pcl_ros
51 {
53  {
54  DiagnosticNodelet::onInit();
55  srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
56  dynamic_reconfigure::Server<Config>::CallbackType f =
57  boost::bind(&ColorHistogram::configCallback, this, _1, _2);
58  srv_->setCallback(f);
59  pub_histogram_ = advertise<jsk_recognition_msgs::ColorHistogramArray>(*pnh_, "output", 1);
61  }
62 
63  void ColorHistogram::configCallback(Config& config, uint32_t level)
64  {
65  boost::mutex::scoped_lock lock(mutex_);
66  bin_size_ = config.bin_size;
68  white_threshold_ = config.white_threshold;
69  black_threshold_ = config.black_threshold;
70  if (queue_size_ != config.queue_size) {
71  queue_size_ = config.queue_size;
72  if (isSubscribed()) {
73  unsubscribe();
74  subscribe();
75  }
76  }
77  }
78 
80  {
81  sub_cloud_.subscribe(*pnh_, "input", 1);
82  sub_indices_.subscribe(*pnh_, "input/indices", 1);
83  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
84  sync_->connectInput(sub_cloud_, sub_indices_);
85  sync_->registerCallback(boost::bind(&ColorHistogram::feature,
86  this, _1, _2));
87  }
88 
90  {
93  }
94 
96  const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
97  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices)
98  {
99  boost::mutex::scoped_lock lock(mutex_);
100 
101  pcl::PointCloud<pcl::PointXYZRGB>::Ptr rgb_cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
102  pcl::fromROSMsg(*input_cloud, *rgb_cloud);
103 
104  pcl::PointCloud<pcl::PointXYZHSV>::Ptr hsv_cloud(new pcl::PointCloud<pcl::PointXYZHSV>);
105  pcl::PointCloudXYZRGBtoXYZHSV(*rgb_cloud, *hsv_cloud);
106 
107  for (size_t i = 0; i < rgb_cloud->points.size(); i++) {
108  hsv_cloud->points[i].x = rgb_cloud->points[i].x;
109  hsv_cloud->points[i].y = rgb_cloud->points[i].y;
110  hsv_cloud->points[i].z = rgb_cloud->points[i].z;
111  }
112 
113  pcl::ExtractIndices<pcl::PointXYZHSV> extract;
114  extract.setInputCloud(hsv_cloud);
115 
116  jsk_recognition_msgs::ColorHistogramArray histogram_array;
117  histogram_array.histograms.resize(input_indices->cluster_indices.size());
118  histogram_array.header = input_cloud->header;
119  for (size_t i = 0; i < input_indices->cluster_indices.size(); ++i) {
120  pcl::IndicesPtr indices(new std::vector<int>(input_indices->cluster_indices[i].indices));
121  extract.setIndices(indices);
122  pcl::PointCloud<pcl::PointXYZHSV> segmented_cloud;
123  extract.filter(segmented_cloud);
124  histogram_array.histograms[i].header = input_cloud->header;
127  histogram_array.histograms[i].histogram,
128  bin_size_,
133  histogram_array.histograms[i].histogram,
134  bin_size_,
137  } else {
138  NODELET_FATAL("Invalid histogram policy");
139  return;
140  }
141  }
142  pub_histogram_.publish(histogram_array);
143  }
144 }
145 
virtual void configCallback(Config &config, uint32_t level)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
ColorHistogramConfig Config
void publish(const boost::shared_ptr< M > &message) const
void computeColorHistogram1d(const pcl::PointCloud< pcl::PointXYZHSV > &cloud, std::vector< float > &histogram, const int bin_size, const double white_threshold=0.1, const double black_threshold=0.1)
void computeColorHistogram2d(const pcl::PointCloud< pcl::PointXYZHSV > &cloud, std::vector< float > &histogram, const int bin_size_per_channel, const double white_threshold=0.1, const double black_threshold=0.1)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ColorHistogram, nodelet::Nodelet)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
boost::shared_ptr< ros::NodeHandle > pnh_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
virtual void feature(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
jsk_recognition_utils::HistogramPolicy histogram_policy_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
#define NODELET_FATAL(...)
void PointCloudXYZRGBtoXYZHSV(PointCloud< PointXYZRGB > &in, PointCloud< PointXYZHSV > &out)
Convert a XYZRGB point cloud to a XYZHSV.


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