color_histogram_matcher_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 
38 #include <pcl/filters/extract_indices.h>
39 #include <pcl/common/centroid.h>
40 #include <geometry_msgs/PoseStamped.h>
41 
42 #include <pcl/pcl_config.h>
43 #if PCL_VERSION_COMPARE (<, 1, 7, 2)
45 #else
47 #endif
48 
49 namespace jsk_pcl_ros
50 {
52  {
53  ConnectionBasedNodelet::onInit();
54  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
55  dynamic_reconfigure::Server<Config>::CallbackType f =
56  boost::bind (&ColorHistogramMatcher::configCallback, this, _1, _2);
57  srv_->setCallback (f);
58 
60  reference_set_ = false;
61  // setup publishers
63  = advertise<jsk_recognition_msgs::ColorHistogramArray>(
64  *pnh_, "output_histograms", 1);
65  best_pub_
66  = advertise<geometry_msgs::PoseStamped>(*pnh_, "best_match", 1);
68  = advertise<jsk_recognition_msgs::ColorHistogram>(*pnh_, "output_reference", 1);
70  = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output", 1);
72  = advertise<sensor_msgs::PointCloud2>(*pnh_, "coefficient_points", 1);
74  }
75 
77  {
78  reference_sub_ = pnh_->subscribe("input_reference_cloud", 1,
80  this);
81  reference_histogram_sub_ = pnh_->subscribe(
82  "input_reference", 1,
84  this);
85  sub_input_.subscribe(*pnh_, "input", 1);
86  sub_indices_.subscribe(*pnh_, "input_indices", 1);
87  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
88  sync_->connectInput(sub_input_, sub_indices_);
89  sync_->registerCallback(boost::bind(&ColorHistogramMatcher::feature,
90  this, _1, _2));
91  }
92 
94  {
99  }
100 
101  void ColorHistogramMatcher::configCallback(Config &config, uint32_t level)
102  {
103  boost::mutex::scoped_lock lock(mutex_);
104  coefficient_thr_ = config.coefficient_thr;
105  bin_size_ = config.bin_size;
106  publish_colored_cloud_ = config.publish_colored_cloud;
107  power_ = config.power;
108  color_min_coefficient_ = config.color_min_coefficient;
109  color_max_coefficient_ = config.color_max_coefficient;
110  show_method_ = config.show_method;
111  ComparePolicy new_histogram;
112  if (config.histogram_method == 0) {
113  new_histogram = USE_HUE;
114  }
115  else if (config.histogram_method == 1) {
116  new_histogram = USE_SATURATION;
117  }
118  else if (config.histogram_method == 2) {
119  new_histogram = USE_VALUE;
120  }
121  else if (config.histogram_method == 3) {
122  new_histogram = USE_HUE_AND_SATURATION;
123  }
124  else {
125  ROS_WARN("unknown histogram method");
126  return;
127  }
128  if (new_histogram != policy_) {
129  policy_ = new_histogram;
130  reference_set_ = false;
131  ROS_WARN("histogram method is reset, please specify histogram again");
132  }
133  }
134 
135 
137  const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
138  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices)
139  {
140  boost::mutex::scoped_lock lock(mutex_);
141  if (!reference_set_) {
142  NODELET_WARN("reference histogram is not available yet");
143  return;
144  }
145  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pcl_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
146  pcl::fromROSMsg(*input_cloud, *pcl_cloud);
147  pcl::PointCloud<pcl::PointXYZHSV>::Ptr hsv_cloud (new pcl::PointCloud<pcl::PointXYZHSV>);
148  pcl::PointCloudXYZRGBtoXYZHSV(*pcl_cloud, *hsv_cloud);
149  for (size_t i = 0; i < pcl_cloud->points.size(); i++) {
150  hsv_cloud->points[i].x = pcl_cloud->points[i].x;
151  hsv_cloud->points[i].y = pcl_cloud->points[i].y;
152  hsv_cloud->points[i].z = pcl_cloud->points[i].z;
153  }
154  // compute histograms first
155  std::vector<std::vector<float> > histograms;
156  histograms.resize(input_indices->cluster_indices.size());
157  unsigned long point_all_size=0;
158  pcl::ExtractIndices<pcl::PointXYZHSV> extract;
159  extract.setInputCloud(hsv_cloud);
160  // for debug
161  jsk_recognition_msgs::ColorHistogramArray histogram_array;
162  histogram_array.header = input_cloud->header;
163  std::vector<pcl::PointCloud<pcl::PointXYZHSV>::Ptr > segmented_clouds;
164  for (size_t i = 0; i < input_indices->cluster_indices.size(); i++) {
165  pcl::IndicesPtr indices (new std::vector<int>(input_indices->cluster_indices[i].indices));
166  point_all_size+=indices->size();
167  extract.setIndices(indices);
168  pcl::PointCloud<pcl::PointXYZHSV> segmented_cloud;
169  extract.filter(segmented_cloud);
170  segmented_clouds.push_back(segmented_cloud.makeShared());
171  std::vector<float> histogram;
172  computeHistogram(segmented_cloud, histogram, policy_);
173  histograms[i] = histogram;
174  jsk_recognition_msgs::ColorHistogram ros_histogram;
175  ros_histogram.header = input_cloud->header;
176  ros_histogram.histogram = histogram;
177  histogram_array.histograms.push_back(ros_histogram);
178  }
179  all_histogram_pub_.publish(histogram_array);
180 
181  // compare histograms
182  jsk_recognition_msgs::ClusterPointIndices result;
183  result.header = input_indices->header;
184  double best_coefficient = - DBL_MAX;
185  int best_index = -1;
186  pcl::PointCloud<pcl::PointXYZRGB>::Ptr output_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
188  output_cloud->width=point_all_size;
189  output_cloud->height=1;
190  output_cloud->resize(point_all_size);
191  }
192  unsigned long count_points=0;
193  for (size_t i = 0; i < input_indices->cluster_indices.size(); i++) {
194  const double coefficient = bhattacharyyaCoefficient(histograms[i], reference_histogram_);
195  NODELET_DEBUG_STREAM("coefficient: " << i << "::" << coefficient);
197  int tmp_point_size = input_indices->cluster_indices[i].indices.size();
198  double color_standard;
199  if(color_min_coefficient_ > coefficient){
200  color_standard = 0;
201  } else if(color_max_coefficient_ < coefficient){
202  color_standard = 1;
203  } else{
204  color_standard = (coefficient - color_min_coefficient_) / (color_max_coefficient_ - color_min_coefficient_);
205  }
206  double color_standard_powered = 1;
207  for (int k=0; k<power_; k++){
208  color_standard_powered *= color_standard;
209  }
210  unsigned char color_r, color_g, color_b;
211  switch(show_method_){
212  case 0:
213  color_r=(int)(255*color_standard_powered);
214  color_g=0;
215  color_b=(int)(255*(1-color_standard_powered));
216  break;
217  case 1:
218  // like thermo
219  int color_index = (int)(color_standard_powered*1280);
220  switch(color_index/256){
221  case 0:
222  color_r=0; color_g=0; color_b=color_index;
223  break;
224  case 1:
225  color_r=color_index-256; color_g=0; color_b=255;
226  break;
227  case 2:
228  color_r=255; color_g=0; color_b=255-(color_index-256*2);
229  break;
230  case 3:
231  color_r=255; color_g=color_index-256*3; color_b=0;
232  break;
233  case 4:
234  color_r=255; color_g=255; color_b=color_index-256*4;
235  break;
236  case 5:
237  color_r=255; color_g=255; color_b=255;
238  break;
239  }
240  break;
241  }
242  for(int j=0; j<tmp_point_size; j++){
243  output_cloud->points[j+count_points].x=segmented_clouds[i]->points[j].x;
244  output_cloud->points[j+count_points].y=segmented_clouds[i]->points[j].y;
245  output_cloud->points[j+count_points].z=segmented_clouds[i]->points[j].z;
246  output_cloud->points[j+count_points].r=color_r;
247  output_cloud->points[j+count_points].g=color_g;
248  output_cloud->points[j+count_points].b=color_b;
249  }
250  count_points+=tmp_point_size;
251  }
252  if (coefficient > coefficient_thr_) {
253  result.cluster_indices.push_back(input_indices->cluster_indices[i]);
254  if (best_coefficient < coefficient) {
255  best_coefficient = coefficient;
256  best_index = i;
257  }
258  }
259  }
260  NODELET_DEBUG("best coefficients: %f, %d", best_coefficient, best_index);
261  //show coefficience with points
262  sensor_msgs::PointCloud2 p_msg;
264  pcl::toROSMsg(*output_cloud, p_msg);
265  p_msg.header=input_cloud->header;
267  }
268  result_pub_.publish(result);
269  if (best_index != -1) {
270  pcl::PointCloud<pcl::PointXYZHSV>::Ptr best_cloud
271  = segmented_clouds[best_index];
272 
273  best_cloud->is_dense = false;
274  Eigen::Vector4f center;
275  pcl::compute3DCentroid(*best_cloud, center);
276  geometry_msgs::PoseStamped best_pose;
277  best_pose.header = input_cloud->header;
278  best_pose.pose.position.x = center[0];
279  best_pose.pose.position.y = center[1];
280  best_pose.pose.position.z = center[2];
281  best_pose.pose.orientation.w = 1.0;
282  best_pub_.publish(best_pose);
283  }
284  }
285 
286  double ColorHistogramMatcher::bhattacharyyaCoefficient(const std::vector<float>& a, const std::vector<float>& b)
287  {
288  if (a.size() != b.size()) {
289  NODELET_ERROR("the bin size of histograms do not match");
290  return 0.0;
291  }
292  double sum = 0.0;
293  for (size_t i = 0; i < a.size(); i++) {
294  sum += sqrt(a[i] * b[i]);
295  }
296  return sum;
297  }
298 
300  const pcl::PointCloud<pcl::PointXYZHSV>& cloud,
301  std::vector<float>& output,
302  const ComparePolicy policy)
303  {
304  if (policy == USE_HUE_AND_SATURATION) {
305  std::vector<float> hue, saturation;
306  computeHistogram(cloud, hue, USE_HUE);
307  computeHistogram(cloud, saturation, USE_SATURATION);
308 
309  output.resize(hue.size() + saturation.size());
310  for (size_t i = 0; i < hue.size(); i++) {
311  output[i] = hue[i];
312  }
313  for (size_t j = hue.size(); j < hue.size() + saturation.size(); j++) {
314  output[j] = saturation[j - hue.size()];
315  }
316  }
317  else {
318  double val_max, val_min;
319  if (policy == USE_HUE) {
320  val_max = 360.0;
321  val_min = 0.0;
322  }
323  else {
324  val_max = 1.0;
325  val_min = 0.0;
326  }
327  output.resize(bin_size_, 0);
328  for (size_t i = 0; i < cloud.points.size(); i++) {
329  pcl::PointXYZHSV output_point = cloud.points[i];
330  // ratil
331  double val;
332  if (policy == USE_HUE) {
333  val = output_point.h;
334  }
335  else if (policy == USE_SATURATION) {
336  val = output_point.s;
337  }
338  else if (policy == USE_VALUE) {
339  val = output_point.v;
340  }
341  int index = int((val - val_min) / (val_max - val_min) * bin_size_);
342  if (index >= bin_size_) {
343  index = bin_size_ - 1;
344  }
345  output[index] += 1.0;
346  }
347  }
348  // normalize
349  double sum = 0;
350  for (size_t i = 0; i < output.size(); i++) {
351  sum += output[i];
352  }
353  for (size_t i = 0; i < output.size(); i++) {
354  if (sum != 0.0) {
355  output[i] /= sum;
356  }
357  else {
358  output[i] = 0.0;
359  }
360  }
361  }
362 
364  const sensor_msgs::PointCloud2::ConstPtr& input_cloud)
365  {
366  boost::mutex::scoped_lock lock(mutex_);
367  std::vector<float> hist;
368  pcl::PointCloud<pcl::PointXYZRGB> pcl_cloud;
369  pcl::fromROSMsg(*input_cloud, pcl_cloud);
370  pcl::PointCloud<pcl::PointXYZHSV> hsv_cloud;
371  pcl::PointCloudXYZRGBtoXYZHSV(pcl_cloud, hsv_cloud);
372  computeHistogram(hsv_cloud, hist, policy_);
373  reference_histogram_ = hist;
374  NODELET_INFO("update reference");
375  reference_set_ = true;
376  jsk_recognition_msgs::ColorHistogram ros_histogram;
377  ros_histogram.header = input_cloud->header;
378  ros_histogram.histogram = reference_histogram_;
379  reference_histogram_pub_.publish(ros_histogram);
380  }
381 
383  const jsk_recognition_msgs::ColorHistogram::ConstPtr& input_histogram)
384  {
385  boost::mutex::scoped_lock lock(mutex_);
386  NODELET_INFO("update reference");
387  reference_histogram_ = input_histogram->histogram;
388  reference_histogram_pub_.publish(input_histogram);
389  reference_set_ = true;
390  }
391 
392 }
393 
virtual void feature(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices)
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void reference(const sensor_msgs::PointCloud2::ConstPtr &input_cloud)
#define ROS_WARN(...)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
unsigned int index
result
virtual double bhattacharyyaCoefficient(const std::vector< float > &a, const std::vector< float > &b)
double sqrt()
boost::shared_ptr< ros::NodeHandle > pnh_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
#define NODELET_DEBUG_STREAM(...)
#define NODELET_INFO(...)
virtual void configCallback(Config &config, uint32_t level)
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)
virtual void referenceHistogram(const jsk_recognition_msgs::ColorHistogram::ConstPtr &input_histogram)
T sum(T *pf, int length)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ColorHistogramMatcher, nodelet::Nodelet)
virtual void computeHistogram(const pcl::PointCloud< pcl::PointXYZHSV > &cloud, std::vector< float > &output, const ComparePolicy policy)
#define NODELET_DEBUG(...)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void PointCloudXYZRGBtoXYZHSV(PointCloud< PointXYZRGB > &in, PointCloud< PointXYZHSV > &out)
Convert a XYZRGB point cloud to a XYZHSV.
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_


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