concave_hull_mask_image.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2017, 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>
38 #if ( CV_MAJOR_VERSION >= 4)
39 #include <opencv2/imgproc/imgproc_c.h>
40 #endif
41 
42 
43 namespace jsk_perception
44 {
46  {
47  DiagnosticNodelet::onInit();
48 
49  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
50  dynamic_reconfigure::Server<Config>::CallbackType f =
51  boost::bind (&ConcaveHullMaskImage::configCallback, this, _1, _2);
52  srv_->setCallback(f);
53 
54  pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
56  }
57 
58  void ConcaveHullMaskImage::configCallback(Config& config, uint32_t level)
59  {
60  boost::mutex::scoped_lock lock(mutex_);
61  min_area_ = config.min_area;
62  max_area_ = config.max_area;
63  }
64 
66  {
67  sub_ = pnh_->subscribe("input", 1, &ConcaveHullMaskImage::concave, this);
68  ros::V_string names = boost::assign::list_of("~input");
70  }
71 
73  {
74  sub_.shutdown();
75  }
76 
77  void ConcaveHullMaskImage::concave(const sensor_msgs::Image::ConstPtr& mask_msg)
78  {
79  vital_checker_->poke();
81  cv::Mat mask = cv_ptr->image;
82 
83  // Find contours
84  std::vector<std::vector<cv::Point> > contours;
85  std::vector<cv::Vec4i> hierarchy;
86  cv::findContours(mask, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
87 
88  int max_area = 0;
89  if (max_area_ < 0) {
90  max_area = mask.cols * mask.rows;
91  } else {
92  max_area = max_area_;
93  }
94 
95  // Prune contours
96  std::vector<std::vector<cv::Point> > pruned_contours;
97  for (size_t i = 0; i < contours.size(); i++) {
98  double area = cv::contourArea(contours[i]);
99  if (min_area_ <= area && area <= max_area) {
100  pruned_contours.push_back(contours[i]);
101  }
102  }
103 
104  // Smooth the contours
105  std::vector<std::vector<cv::Point> > smoothed_contours;
106  smoothed_contours.resize(pruned_contours.size());
107  for (size_t i = 0; i < pruned_contours.size(); i++) {
108  std::vector<float> x;
109  std::vector<float> y;
110  const size_t n = pruned_contours[i].size();
111 
112  for (size_t j = 0; j < n; j++) {
113  x.push_back(pruned_contours[i][j].x);
114  y.push_back(pruned_contours[i][j].y);
115  }
116 
117  cv::Mat G;
118  cv::transpose(cv::getGaussianKernel(11, 4.0, CV_32FC1), G);
119 
120  std::vector<float> x_smooth;
121  std::vector<float> y_smooth;
122 
123  cv::filter2D(x, x_smooth, CV_32FC1, G);
124  cv::filter2D(y, y_smooth, CV_32FC1, G);
125 
126  for (size_t j = 0; j < n; j++) {
127  smoothed_contours[i].push_back(cv::Point2f(x_smooth[j], y_smooth[j]));
128  }
129  }
130 
131  cv::Mat concave_hull_mask = cv::Mat::zeros(mask.size(), mask.type());
132  for (size_t i = 0; i < smoothed_contours.size(); i++) {
133  cv::drawContours(concave_hull_mask, smoothed_contours, i, cv::Scalar(255), CV_FILLED);
134  }
135 
136  pub_.publish(cv_bridge::CvImage(mask_msg->header,
138  concave_hull_mask).toImageMsg());
139 
140  }
141 
142 } // namespace jsk_perception
143 
f
void publish(const boost::shared_ptr< M > &message) const
PLUGINLIB_EXPORT_CLASS(jsk_perception::ConcaveHullMaskImage, nodelet::Nodelet)
GLfloat n[6][3]
virtual void configCallback(Config &config, uint32_t level)
jsk_perception::ConcaveHullMaskImageConfig Config
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void concave(const sensor_msgs::Image::ConstPtr &mask_msg)
std::vector< std::string > V_string
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())
x
y
jsk_topic_tools::VitalChecker::Ptr vital_checker_
mutex_t * lock
sensor_msgs::ImagePtr toImageMsg() const


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