filter_mask_image_with_size.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 #include <boost/assign.hpp>
38 #include <opencv2/opencv.hpp>
39 #include <cv_bridge/cv_bridge.h>
41 
42 namespace jsk_perception
43 {
45  {
46  DiagnosticNodelet::onInit();
47  pnh_->param("approximate_sync", approximate_sync_, false);
48  pnh_->param("queue_size", queue_size_, 100);
49  pnh_->param("use_reference", use_reference_, false);
50  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
51  dynamic_reconfigure::Server<Config>::CallbackType f =
52  boost::bind(&FilterMaskImageWithSize::configCallback, this, _1, _2);
53  srv_->setCallback(f);
54  pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
56  }
57 
59  Config &config, uint32_t level)
60  {
61  boost::mutex::scoped_lock lock(mutex_);
62  min_size_ = config.min_size;
63  max_size_ = config.max_size;
64  if (use_reference_)
65  {
66  min_relative_size_ = config.min_relative_size;
67  max_relative_size_ = config.max_relative_size;
68  }
69  else
70  {
71  if ((config.min_relative_size != 0) || (config.max_relative_size != 1))
72  {
73  ROS_WARN("Rosparam ~min_relative_size and ~max_relative_size is enabled only with ~use_reference is true,"
74  " and will be overwritten by 0 and 1.");
75  }
76  min_relative_size_ = config.min_relative_size = 0;
77  max_relative_size_ = config.max_relative_size = 1;
78  }
79  }
80 
82  {
83  sub_input_.subscribe(*pnh_, "input", 1);
84  ros::V_string names = boost::assign::list_of("~input");
85  if (use_reference_)
86  {
87  sub_reference_.subscribe(*pnh_, "input/reference", 1);
89  {
90  async_ = boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicy> >(queue_size_);
91  async_->connectInput(sub_input_, sub_reference_);
92  async_->registerCallback(boost::bind(&FilterMaskImageWithSize::filter, this, _1, _2));
93  }
94  else
95  {
96  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
97  sync_->connectInput(sub_input_, sub_reference_);
98  sync_->registerCallback(boost::bind(&FilterMaskImageWithSize::filter, this, _1, _2));
99  }
100  names.push_back("~input/reference");
101  }
102  else
103  {
105  }
107  }
108 
110  {
112  if (use_reference_)
113  {
115  }
116  }
117 
119  const sensor_msgs::Image::ConstPtr& input_msg)
120  {
121  filter(input_msg, input_msg);
122  }
123 
125  const sensor_msgs::Image::ConstPtr& input_msg,
126  const sensor_msgs::Image::ConstPtr& reference_msg)
127  {
128  if ((input_msg->height != reference_msg->height) ||
129  (input_msg->width != reference_msg->width))
130  {
131  ROS_FATAL("Input mask size must match. input: (%d, %d), reference: (%d, %d)",
132  input_msg->height, input_msg->width,
133  reference_msg->height, reference_msg->width);
134  return;
135  }
136  cv::Mat input = cv_bridge::toCvShare(input_msg, input_msg->encoding)->image;
137  cv::Mat reference = cv_bridge::toCvShare(reference_msg, reference_msg->encoding)->image;
138  double size_image = input_msg->height * input_msg->width;
139  double size_input = cv::countNonZero(input > 127) / size_image;
140  double size_reference = cv::countNonZero(reference > 127) / size_image;
141  double size_relative = size_input / size_reference;
142  ROS_INFO("image relative: %lf <= %lf <= %lf, mask relative: %lf <= %lf <= %lf",
143  min_size_, size_input, max_size_,
144  min_relative_size_, size_relative, max_relative_size_);
145  if (!std::isnan(size_relative) &&
146  (min_size_ <= size_input) && (size_input <= max_size_) &&
147  (min_relative_size_ <= size_relative) && (size_relative <= max_relative_size_))
148  {
149  pub_.publish(input_msg);
150  }
151  }
152 } // namespace jsk_perception
153 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
f
PLUGINLIB_EXPORT_CLASS(jsk_perception::FilterMaskImageWithSize, nodelet::Nodelet)
#define ROS_FATAL(...)
virtual void configCallback(Config &config, uint32_t level)
jsk_perception::FilterMaskImageWithSizeConfig Config
boost::shared_ptr< message_filters::Synchronizer< ApproxSyncPolicy > > async_
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber< sensor_msgs::Image > sub_reference_
#define ROS_WARN(...)
input
std::vector< std::string > V_string
#define ROS_INFO(...)
boost::shared_ptr< ros::NodeHandle > pnh_
bool warnNoRemap(const std::vector< std::string > names)
message_filters::Subscriber< sensor_msgs::Image > sub_input_
mutex_t * lock
virtual void filter(const sensor_msgs::Image::ConstPtr &input_msg)
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)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Connection registerCallback(const C &callback)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_


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