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/or 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>
38 #include <jsk_topic_tools/log_utils.h>
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);
56  onInitPostProcess();
57  }
58 
60  // message_filters::Synchronizer needs to be called reset
61  // before message_filters::Subscriber is freed.
62  // Calling reset fixes the following error on shutdown of the nodelet:
63  // terminate called after throwing an instance of
64  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
65  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
66  // Also see https://github.com/ros/ros_comm/issues/720 .
67  sync_.reset();
68  }
69 
71  {
72  ros::V_string names;
73  if (use_mask_) {
74  sub_image_.subscribe(*pnh_, "input", 1);
75  sub_mask_.subscribe(*pnh_, "input/mask", 1);
76  names.push_back("~input");
77  names.push_back("~input/mask");
78  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
79  sync_->connectInput(sub_image_, sub_mask_);
80  sync_->registerCallback(boost::bind(&SingleChannelHistogram::compute,
81  this, _1, _2));
82  }
83  else {
84  sub_ = pnh_->subscribe("input", 1,
86  this);
87  names.push_back("~input");
88  }
89  jsk_topic_tools::warnNoRemap(names);
90  }
91 
93  {
94  if (use_mask_) {
97  }
98  else {
99  sub_.shutdown();
100  }
101  }
102 
104  const sensor_msgs::Image::ConstPtr& msg,
105  const sensor_msgs::Image::ConstPtr& mask_msg)
106  {
107  boost::mutex::scoped_lock lock(mutex_);
108  cv::Mat image = cv_bridge::toCvCopy(msg, msg->encoding)->image;
109  cv::Mat mask;
110  if (mask_msg) {
111  mask = cv_bridge::toCvCopy(mask_msg, mask_msg->encoding)->image;
112  }
113  float range[] = { min_value_, max_value_ } ;
114  const float* histRange = { range };
115  cv::MatND hist;
116  bool uniform = true; bool accumulate = false;
117 
118  cv::calcHist(&image, 1, 0, mask, hist, 1, &hist_size_,
119  &histRange, uniform, accumulate);
120  jsk_recognition_msgs::ColorHistogram histogram;
121  histogram.header = msg->header;
122  for (int i = 0; i < hist_size_; i++) {
123  histogram.histogram.push_back(hist.at<float>(0, i));
124  }
125  pub_.publish(histogram);
126  }
127 
129  const sensor_msgs::Image::ConstPtr& msg)
130  {
131  compute(msg, sensor_msgs::Image::ConstPtr());
132  }
133 
135  Config &config, uint32_t level)
136  {
137  boost::mutex::scoped_lock lock(mutex_);
138  hist_size_ = config.hist_size;
139  min_value_ = config.min_value;
140  max_value_ = config.max_value;
141  }
142 }
143 
jsk_perception::SingleChannelHistogram::unsubscribe
virtual void unsubscribe()
Definition: single_channel_histogram.cpp:124
msg
msg
i
int i
jsk_perception::SingleChannelHistogram::use_mask_
bool use_mask_
Definition: single_channel_histogram.h:142
ros::Subscriber::shutdown
void shutdown()
jsk_perception::SingleChannelHistogram::onInit
virtual void onInit()
Definition: single_channel_histogram.cpp:76
jsk_perception::SingleChannelHistogram::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: single_channel_histogram.cpp:166
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
class_list_macros.h
jsk_perception::SingleChannelHistogram::max_value_
float max_value_
Definition: single_channel_histogram.h:148
jsk_perception
Definition: add_mask_image.h:48
single_channel_histogram.h
jsk_perception::SingleChannelHistogram::pub_
ros::Publisher pub_
Definition: single_channel_histogram.h:144
jsk_perception::SingleChannelHistogram::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: single_channel_histogram.h:138
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
jsk_perception::SingleChannelHistogram::sub_image_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
Definition: single_channel_histogram.h:139
jsk_perception::SingleChannelHistogram::~SingleChannelHistogram
virtual ~SingleChannelHistogram()
Definition: single_channel_histogram.cpp:91
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_perception::SingleChannelHistogram, nodelet::Nodelet)
jsk_perception::SingleChannelHistogram::min_value_
float min_value_
Definition: single_channel_histogram.h:147
hist
hist
lock
mutex_t * lock
message_filters::Subscriber::subscribe
void subscribe()
f
f
nodelet::Nodelet
jsk_perception::SingleChannelHistogram::compute
virtual void compute(const sensor_msgs::Image::ConstPtr &msg)
Definition: single_channel_histogram.cpp:160
cv_bridge.h
jsk_perception::SingleChannelHistogram::sub_mask_
message_filters::Subscriber< sensor_msgs::Image > sub_mask_
Definition: single_channel_histogram.h:140
jsk_perception::SingleChannelHistogram::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: single_channel_histogram.h:141
ros::V_string
std::vector< std::string > V_string
jsk_perception::SingleChannelHistogram::hist_size_
int hist_size_
Definition: single_channel_histogram.h:146
config
config
jsk_perception::SingleChannelHistogram::sub_
ros::Subscriber sub_
Definition: single_channel_histogram.h:143
jsk_perception::SingleChannelHistogram::mutex_
boost::mutex mutex_
Definition: single_channel_histogram.h:145
jsk_perception::SingleChannelHistogram::subscribe
virtual void subscribe()
Definition: single_channel_histogram.cpp:102
jsk_perception::SingleChannelHistogram
Definition: single_channel_histogram.h:86
jsk_perception::SingleChannelHistogram::Config
SingleChannelHistogramConfig Config
Definition: single_channel_histogram.h:124


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17