Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #include <jsk_pcl_ros/color_histogram.h>
00041 #include <pcl/filters/extract_indices.h>
00042
00043 #include <pcl/pcl_config.h>
00044 #if PCL_VERSION_COMPARE (<, 1, 7, 2)
00045 #include <jsk_pcl_ros/pcl/point_types_conversion.h>
00046 #else
00047 #include <pcl/point_types_conversion.h>
00048 #endif
00049
00050 namespace jsk_pcl_ros
00051 {
00052 void ColorHistogram::onInit()
00053 {
00054 DiagnosticNodelet::onInit();
00055 srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00056 dynamic_reconfigure::Server<Config>::CallbackType f =
00057 boost::bind(&ColorHistogram::configCallback, this, _1, _2);
00058 srv_->setCallback(f);
00059 pub_histogram_ = advertise<jsk_recognition_msgs::ColorHistogramArray>(*pnh_, "output", 1);
00060 onInitPostProcess();
00061 }
00062
00063 void ColorHistogram::configCallback(Config& config, uint32_t level)
00064 {
00065 boost::mutex::scoped_lock lock(mutex_);
00066 bin_size_ = config.bin_size;
00067 histogram_policy_ = jsk_recognition_utils::HistogramPolicy(config.histogram_policy);
00068 white_threshold_ = config.white_threshold;
00069 black_threshold_ = config.black_threshold;
00070 if (queue_size_ != config.queue_size) {
00071 queue_size_ = config.queue_size;
00072 if (isSubscribed()) {
00073 unsubscribe();
00074 subscribe();
00075 }
00076 }
00077 }
00078
00079 void ColorHistogram::subscribe()
00080 {
00081 sub_cloud_.subscribe(*pnh_, "input", 1);
00082 sub_indices_.subscribe(*pnh_, "input/indices", 1);
00083 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
00084 sync_->connectInput(sub_cloud_, sub_indices_);
00085 sync_->registerCallback(boost::bind(&ColorHistogram::feature,
00086 this, _1, _2));
00087 }
00088
00089 void ColorHistogram::unsubscribe()
00090 {
00091 sub_cloud_.unsubscribe();
00092 sub_indices_.unsubscribe();
00093 }
00094
00095 void ColorHistogram::feature(
00096 const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
00097 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices)
00098 {
00099 boost::mutex::scoped_lock lock(mutex_);
00100
00101 pcl::PointCloud<pcl::PointXYZRGB>::Ptr rgb_cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
00102 pcl::fromROSMsg(*input_cloud, *rgb_cloud);
00103
00104 pcl::PointCloud<pcl::PointXYZHSV>::Ptr hsv_cloud(new pcl::PointCloud<pcl::PointXYZHSV>);
00105 pcl::PointCloudXYZRGBtoXYZHSV(*rgb_cloud, *hsv_cloud);
00106
00107 for (size_t i = 0; i < rgb_cloud->points.size(); i++) {
00108 hsv_cloud->points[i].x = rgb_cloud->points[i].x;
00109 hsv_cloud->points[i].y = rgb_cloud->points[i].y;
00110 hsv_cloud->points[i].z = rgb_cloud->points[i].z;
00111 }
00112
00113 pcl::ExtractIndices<pcl::PointXYZHSV> extract;
00114 extract.setInputCloud(hsv_cloud);
00115
00116 jsk_recognition_msgs::ColorHistogramArray histogram_array;
00117 histogram_array.histograms.resize(input_indices->cluster_indices.size());
00118 histogram_array.header = input_cloud->header;
00119 for (size_t i = 0; i < input_indices->cluster_indices.size(); ++i) {
00120 pcl::IndicesPtr indices(new std::vector<int>(input_indices->cluster_indices[i].indices));
00121 extract.setIndices(indices);
00122 pcl::PointCloud<pcl::PointXYZHSV> segmented_cloud;
00123 extract.filter(segmented_cloud);
00124 histogram_array.histograms[i].header = input_cloud->header;
00125 if (histogram_policy_ == jsk_recognition_utils::HUE) {
00126 jsk_recognition_utils::computeColorHistogram1d(segmented_cloud,
00127 histogram_array.histograms[i].histogram,
00128 bin_size_,
00129 white_threshold_,
00130 black_threshold_);
00131 } else if (histogram_policy_ == jsk_recognition_utils::HUE_AND_SATURATION) {
00132 jsk_recognition_utils::computeColorHistogram2d(segmented_cloud,
00133 histogram_array.histograms[i].histogram,
00134 bin_size_,
00135 white_threshold_,
00136 black_threshold_);
00137 } else {
00138 NODELET_FATAL("Invalid histogram policy");
00139 return;
00140 }
00141 }
00142 pub_histogram_.publish(histogram_array);
00143 }
00144 }
00145
00146 #include <pluginlib/class_list_macros.h>
00147 PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ColorHistogram, nodelet::Nodelet);