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 #include "jsk_perception/single_channel_histogram.h"
00037 #include <boost/assign.hpp>
00038 #include <jsk_topic_tools/log_utils.h>
00039 #include <opencv2/opencv.hpp>
00040 #include <cv_bridge/cv_bridge.h>
00041
00042 namespace jsk_perception
00043 {
00044 void SingleChannelHistogram::onInit()
00045 {
00046 DiagnosticNodelet::onInit();
00047 pnh_->param("use_mask", use_mask_, false);
00048 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00049 dynamic_reconfigure::Server<Config>::CallbackType f =
00050 boost::bind (
00051 &SingleChannelHistogram::configCallback, this, _1, _2);
00052 srv_->setCallback (f);
00053
00054 pub_ = advertise<jsk_recognition_msgs::ColorHistogram>(
00055 *pnh_, "output", 1);
00056 onInitPostProcess();
00057 }
00058
00059 void SingleChannelHistogram::subscribe()
00060 {
00061 ros::V_string names;
00062 if (use_mask_) {
00063 sub_image_.subscribe(*pnh_, "input", 1);
00064 sub_mask_.subscribe(*pnh_, "input/mask", 1);
00065 names.push_back("~input");
00066 names.push_back("~input/mask");
00067 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00068 sync_->connectInput(sub_image_, sub_mask_);
00069 sync_->registerCallback(boost::bind(&SingleChannelHistogram::compute,
00070 this, _1, _2));
00071 }
00072 else {
00073 sub_ = pnh_->subscribe("input", 1,
00074 &SingleChannelHistogram::compute,
00075 this);
00076 names.push_back("~input");
00077 }
00078 jsk_topic_tools::warnNoRemap(names);
00079 }
00080
00081 void SingleChannelHistogram::unsubscribe()
00082 {
00083 if (use_mask_) {
00084 sub_image_.unsubscribe();
00085 sub_mask_.unsubscribe();
00086 }
00087 else {
00088 sub_.shutdown();
00089 }
00090 }
00091
00092 void SingleChannelHistogram::compute(
00093 const sensor_msgs::Image::ConstPtr& msg,
00094 const sensor_msgs::Image::ConstPtr& mask_msg)
00095 {
00096 boost::mutex::scoped_lock lock(mutex_);
00097 cv::Mat image = cv_bridge::toCvCopy(msg, msg->encoding)->image;
00098 cv::Mat mask;
00099 if (mask_msg) {
00100 mask = cv_bridge::toCvCopy(mask_msg, mask_msg->encoding)->image;
00101 }
00102 float range[] = { min_value_, max_value_ } ;
00103 const float* histRange = { range };
00104 cv::MatND hist;
00105 bool uniform = true; bool accumulate = false;
00106
00107 cv::calcHist(&image, 1, 0, mask, hist, 1, &hist_size_,
00108 &histRange, uniform, accumulate);
00109 jsk_recognition_msgs::ColorHistogram histogram;
00110 histogram.header = msg->header;
00111 for (int i = 0; i < hist_size_; i++) {
00112 histogram.histogram.push_back(hist.at<float>(0, i));
00113 }
00114 pub_.publish(histogram);
00115 }
00116
00117 void SingleChannelHistogram::compute(
00118 const sensor_msgs::Image::ConstPtr& msg)
00119 {
00120 compute(msg, sensor_msgs::Image::ConstPtr());
00121 }
00122
00123 void SingleChannelHistogram::configCallback(
00124 Config &config, uint32_t level)
00125 {
00126 boost::mutex::scoped_lock lock(mutex_);
00127 hist_size_ = config.hist_size;
00128 min_value_ = config.min_value;
00129 max_value_ = config.max_value;
00130 }
00131 }
00132
00133 #include <pluginlib/class_list_macros.h>
00134 PLUGINLIB_EXPORT_CLASS (jsk_perception::SingleChannelHistogram, nodelet::Nodelet);