concave_hull_mask_image.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2017, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include "jsk_perception/concave_hull_mask_image.h"
00037 #include <boost/assign.hpp>
00038 
00039 
00040 namespace jsk_perception
00041 {
00042   void ConcaveHullMaskImage::onInit()
00043   {
00044     DiagnosticNodelet::onInit();
00045 
00046     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00047     dynamic_reconfigure::Server<Config>::CallbackType f =
00048         boost::bind (&ConcaveHullMaskImage::configCallback, this, _1, _2);
00049     srv_->setCallback(f);
00050 
00051     pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00052     onInitPostProcess();
00053   }
00054 
00055   void ConcaveHullMaskImage::configCallback(Config& config, uint32_t level)
00056   {
00057     boost::mutex::scoped_lock lock(mutex_);
00058     min_area_ = config.min_area;
00059     max_area_ = config.max_area;
00060   }
00061 
00062   void ConcaveHullMaskImage::subscribe()
00063   {
00064     sub_ = pnh_->subscribe("input", 1, &ConcaveHullMaskImage::concave, this);
00065     ros::V_string names = boost::assign::list_of("~input");
00066     jsk_topic_tools::warnNoRemap(names);
00067   }
00068 
00069   void ConcaveHullMaskImage::unsubscribe()
00070   {
00071     sub_.shutdown();
00072   }
00073 
00074   void ConcaveHullMaskImage::concave(const sensor_msgs::Image::ConstPtr& mask_msg)
00075   {
00076     vital_checker_->poke();
00077     cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(mask_msg, sensor_msgs::image_encodings::MONO8);
00078     cv::Mat mask = cv_ptr->image;
00079 
00080     // Find contours
00081     std::vector<std::vector<cv::Point> > contours;
00082     std::vector<cv::Vec4i> hierarchy;
00083     cv::findContours(mask, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
00084 
00085     int max_area = 0;
00086     if (max_area_ < 0) {
00087       max_area = mask.cols * mask.rows;
00088     } else {
00089       max_area = max_area_;
00090     }
00091 
00092     // Prune contours
00093     std::vector<std::vector<cv::Point> > pruned_contours;
00094     for (size_t i = 0; i < contours.size(); i++) {
00095       double area = cv::contourArea(contours[i]);
00096       if (min_area_ <= area && area <= max_area) {
00097         pruned_contours.push_back(contours[i]);
00098       }
00099     }
00100 
00101     // Smooth the contours
00102     std::vector<std::vector<cv::Point> > smoothed_contours;
00103     smoothed_contours.resize(pruned_contours.size());
00104     for (size_t i = 0; i < pruned_contours.size(); i++) {
00105       std::vector<float> x;
00106       std::vector<float> y;
00107       const size_t n = pruned_contours[i].size();
00108 
00109       for (size_t j = 0; j < n; j++) {
00110         x.push_back(pruned_contours[i][j].x);
00111         y.push_back(pruned_contours[i][j].y);
00112       }
00113 
00114       cv::Mat G;
00115       cv::transpose(cv::getGaussianKernel(11, 4.0, CV_32FC1), G);
00116 
00117       std::vector<float> x_smooth;
00118       std::vector<float> y_smooth;
00119 
00120       cv::filter2D(x, x_smooth, CV_32FC1, G);
00121       cv::filter2D(y, y_smooth, CV_32FC1, G);
00122 
00123       for (size_t j = 0; j < n; j++) {
00124         smoothed_contours[i].push_back(cv::Point2f(x_smooth[j], y_smooth[j]));
00125       }
00126     }
00127 
00128     cv::Mat concave_hull_mask = cv::Mat::zeros(mask.size(), mask.type());
00129     for (size_t i = 0; i < smoothed_contours.size(); i++) {
00130       cv::drawContours(concave_hull_mask, smoothed_contours, i, cv::Scalar(255), CV_FILLED);
00131     }
00132 
00133     pub_.publish(cv_bridge::CvImage(mask_msg->header,
00134                                     sensor_msgs::image_encodings::MONO8,
00135                                     concave_hull_mask).toImageMsg());
00136 
00137   }
00138 
00139 }  // namespace jsk_perception
00140 
00141 #include <pluginlib/class_list_macros.h>
00142 PLUGINLIB_EXPORT_CLASS(jsk_perception::ConcaveHullMaskImage, nodelet::Nodelet);


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:07