00001 // -*- mode: C++ -*- 00002 /********************************************************************* 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2013, Ryohei Ueda and JSK Lab 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/o2r other materials provided 00017 * with the distribution. 00018 * * Neither the name of the JSK Lab nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 *********************************************************************/ 00035 00036 #ifndef JSK_PCL_ROS_COLOR_HISTOGRAM_H_ 00037 #define JSK_PCL_ROS_COLOR_HISTOGRAM_H_ 00038 00039 #include <pcl_ros/pcl_nodelet.h> 00040 00041 #include <message_filters/subscriber.h> 00042 #include <message_filters/time_synchronizer.h> 00043 #include <message_filters/synchronizer.h> 00044 00045 #include <jsk_recognition_msgs/ColorHistogram.h> 00046 #include <jsk_recognition_msgs/ColorHistogramArray.h> 00047 #include <sensor_msgs/PointCloud2.h> 00048 #include <jsk_recognition_msgs/ClusterPointIndices.h> 00049 #include "jsk_recognition_utils/pcl_conversion_util.h" 00050 #include <dynamic_reconfigure/server.h> 00051 #include <jsk_pcl_ros/ColorHistogramMatcherConfig.h> 00052 00053 #include "jsk_topic_tools/connection_based_nodelet.h" 00054 00055 namespace jsk_pcl_ros 00056 { 00057 class ColorHistogramMatcher : public jsk_topic_tools::ConnectionBasedNodelet 00058 { 00059 public: 00060 typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, 00061 jsk_recognition_msgs::ClusterPointIndices > SyncPolicy; 00062 typedef ColorHistogramMatcherConfig Config; 00063 enum ComparePolicy { 00064 USE_HUE, 00065 USE_SATURATION, 00066 USE_VALUE, 00067 USE_HUE_AND_SATURATION 00068 }; 00069 protected: 00070 virtual void onInit(); 00071 virtual void feature( 00072 const sensor_msgs::PointCloud2::ConstPtr& input_cloud, 00073 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices); 00074 virtual void reference( 00075 const sensor_msgs::PointCloud2::ConstPtr& input_cloud); 00076 virtual void referenceHistogram( 00077 const jsk_recognition_msgs::ColorHistogram::ConstPtr& input_histogram); 00078 virtual void computeHistogram(const pcl::PointCloud<pcl::PointXYZHSV>& cloud, 00079 std::vector<float>& output, 00080 const ComparePolicy policy); 00081 virtual double bhattacharyyaCoefficient(const std::vector<float>& a, 00082 const std::vector<float>& b); 00083 virtual void configCallback(Config &config, uint32_t level); 00084 virtual void subscribe(); 00085 virtual void unsubscribe(); 00086 boost::mutex mutex_; 00087 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_; 00088 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_; 00089 message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_indices_; 00090 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_; 00091 ros::Subscriber reference_sub_; 00092 ros::Subscriber reference_histogram_sub_; 00093 ros::Publisher result_pub_; 00094 ros::Publisher all_histogram_pub_; 00095 ros::Publisher reference_histogram_pub_; 00096 ros::Publisher best_pub_; 00097 ros::Publisher coefficient_points_pub_; 00098 std::vector<float> reference_histogram_; 00099 bool reference_set_; 00100 double coefficient_thr_; 00101 int bin_size_; 00102 bool publish_colored_cloud_; 00103 int power_; 00104 double color_min_coefficient_; 00105 double color_max_coefficient_; 00106 int show_method_; 00107 // must be exclusive 00108 ComparePolicy policy_; 00109 private: 00110 00111 }; 00112 00113 } 00114 00115 #endif