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