single_channel_histogram.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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 
37 #include <boost/assign.hpp>
39 #include <opencv2/opencv.hpp>
40 #include <cv_bridge/cv_bridge.h>
41 
42 namespace jsk_perception
43 {
45  {
46  DiagnosticNodelet::onInit();
47  pnh_->param("use_mask", use_mask_, false);
48  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
49  dynamic_reconfigure::Server<Config>::CallbackType f =
50  boost::bind (
52  srv_->setCallback (f);
53 
54  pub_ = advertise<jsk_recognition_msgs::ColorHistogram>(
55  *pnh_, "output", 1);
57  }
58 
60  {
61  ros::V_string names;
62  if (use_mask_) {
63  sub_image_.subscribe(*pnh_, "input", 1);
64  sub_mask_.subscribe(*pnh_, "input/mask", 1);
65  names.push_back("~input");
66  names.push_back("~input/mask");
67  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
68  sync_->connectInput(sub_image_, sub_mask_);
69  sync_->registerCallback(boost::bind(&SingleChannelHistogram::compute,
70  this, _1, _2));
71  }
72  else {
73  sub_ = pnh_->subscribe("input", 1,
75  this);
76  names.push_back("~input");
77  }
79  }
80 
82  {
83  if (use_mask_) {
86  }
87  else {
88  sub_.shutdown();
89  }
90  }
91 
93  const sensor_msgs::Image::ConstPtr& msg,
94  const sensor_msgs::Image::ConstPtr& mask_msg)
95  {
96  boost::mutex::scoped_lock lock(mutex_);
97  cv::Mat image = cv_bridge::toCvCopy(msg, msg->encoding)->image;
98  cv::Mat mask;
99  if (mask_msg) {
100  mask = cv_bridge::toCvCopy(mask_msg, mask_msg->encoding)->image;
101  }
102  float range[] = { min_value_, max_value_ } ;
103  const float* histRange = { range };
104  cv::MatND hist;
105  bool uniform = true; bool accumulate = false;
106 
107  cv::calcHist(&image, 1, 0, mask, hist, 1, &hist_size_,
108  &histRange, uniform, accumulate);
109  jsk_recognition_msgs::ColorHistogram histogram;
110  histogram.header = msg->header;
111  for (int i = 0; i < hist_size_; i++) {
112  histogram.histogram.push_back(hist.at<float>(0, i));
113  }
114  pub_.publish(histogram);
115  }
116 
118  const sensor_msgs::Image::ConstPtr& msg)
119  {
120  compute(msg, sensor_msgs::Image::ConstPtr());
121  }
122 
124  Config &config, uint32_t level)
125  {
126  boost::mutex::scoped_lock lock(mutex_);
127  hist_size_ = config.hist_size;
128  min_value_ = config.min_value;
129  max_value_ = config.max_value;
130  }
131 }
132 
f
void publish(const boost::shared_ptr< M > &message) const
virtual void configCallback(Config &config, uint32_t level)
PLUGINLIB_EXPORT_CLASS(jsk_perception::SingleChannelHistogram, nodelet::Nodelet)
hist
virtual void compute(const sensor_msgs::Image::ConstPtr &msg)
std::vector< std::string > V_string
message_filters::Subscriber< sensor_msgs::Image > sub_image_
boost::shared_ptr< ros::NodeHandle > pnh_
bool warnNoRemap(const std::vector< std::string > names)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
mutex_t * lock
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)
message_filters::Subscriber< sensor_msgs::Image > sub_mask_


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27