bing.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2016, 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/bing.h"
00037 #include <ros/ros.h>
00038 #include <rospack/rospack.h>
00039 #include <boost/assign.hpp>
00040 #include <boost/filesystem.hpp>
00041 #include <sensor_msgs/image_encodings.h>
00042 #include <jsk_topic_tools/log_utils.h>
00043 #include <jsk_recognition_msgs/RectArray.h>
00044 #include <cv_bridge/cv_bridge.h>
00045 #include <opencv2/opencv.hpp>
00046 #include <opencv2/saliency.hpp>
00047 #include <vector>
00048 #include <algorithm>
00049 
00050 namespace jsk_perception
00051 {
00052   void Bing::onInit()
00053   {
00054     DiagnosticNodelet::onInit();
00055     pub_rects_ = advertise<jsk_recognition_msgs::RectArray>(*pnh_, "output", 1);
00056     pub_objectness_ = advertise<sensor_msgs::Image>(*pnh_, "output/objectness", 1);
00057     // find trained data
00058     std::string training_path;
00059 #ifdef ROSPACK_EXPORT
00060     rospack::ROSPack rp;
00061     rospack::Package *p = rp.get_pkg("jsk_perception");
00062     if (p == NULL) {
00063       ROS_ERROR("Package path of 'jsk_perception' does not found");
00064       exit(1);
00065     } else {
00066        training_path = p->path + std::string("/trained_data/ObjectnessTrainedModel");
00067     }
00068 #else
00069     rospack::Rospack rp;
00070     ros::V_string search_path;
00071     rp.getSearchPathFromEnv(search_path);
00072     rp.crawl(search_path, 1);
00073     std::string path;
00074     if (rp.find("jsk_perception", path) == true) {
00075       training_path = path + std::string("/trained_data/ObjectnessTrainedModel");
00076     } else {
00077       ROS_ERROR("Package path of 'jsk_perception' does not found");
00078       exit(1);
00079     }
00080 #endif
00081     if (!boost::filesystem::exists(training_path)) {
00082       ROS_ERROR("Training data path '%s' does not exist", training_path.c_str());
00083       exit(1);
00084     }
00085     // setup bing
00086     binger_ = new cv::saliency::ObjectnessBING();
00087     binger_->setTrainingPath(training_path);
00088     onInitPostProcess();
00089   }
00090 
00091   void Bing::subscribe()
00092   {
00093     sub_ = pnh_->subscribe("input", 1, &Bing::apply, this);
00094     ros::V_string names = boost::assign::list_of("~input");
00095     jsk_topic_tools::warnNoRemap(names);
00096   }
00097 
00098   void Bing::unsubscribe()
00099   {
00100     sub_.shutdown();
00101   }
00102 
00103   void Bing::apply(
00104     const sensor_msgs::Image::ConstPtr& img_msg)
00105   {
00106     cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00107       img_msg, img_msg->encoding);
00108     cv::Mat img = cv_ptr->image;
00109 
00110     // Resize too large image for fast processing
00111     double scale = 1.0;
00112     if (img.rows * img.cols > 250000) {
00113       scale = static_cast<double>(std::min(500. / img.rows, 500. / img.cols));
00114       cv::resize(img, img, cv::Size(static_cast<int>(scale * img.cols),
00115                                     static_cast<int>(scale * img.rows)));
00116     }
00117 
00118     std::vector<cv::Vec4i> saliency_map;
00119     binger_->computeSaliency(img, saliency_map);
00120     std::vector<float> objectness_values = binger_->getobjectnessValues();
00121 
00122     jsk_recognition_msgs::RectArray rects_msg;
00123     cv::Mat objectness_img = cv::Mat(img.rows, img.cols, CV_32FC1);
00124     for (size_t k=0; k < saliency_map.size(); k++) {
00125       int min_x = static_cast<int>(saliency_map[k][0] / scale);
00126       int min_y = static_cast<int>(saliency_map[k][1] / scale);
00127       int max_x = static_cast<int>(saliency_map[k][2] / scale);
00128       int max_y = static_cast<int>(saliency_map[k][3] / scale);
00129       // set a proposal
00130       jsk_recognition_msgs::Rect rect;
00131       rect.x = min_x;
00132       rect.y = min_y;
00133       rect.width = max_x - min_x;
00134       rect.height = max_y - min_y;
00135       rects_msg.rects.push_back(rect);
00136       // set objectness
00137       for (size_t j=std::max(0, min_y); j < std::min(max_y, img.rows); j++) {
00138         for (size_t i=std::max(0, min_x); i < std::min(max_x, img.cols); i++) {
00139           objectness_img.at<float>(j, i) += objectness_values[k];
00140         }
00141       }
00142     }
00143     // publish proposals
00144     rects_msg.header = img_msg->header;
00145     pub_rects_.publish(rects_msg);
00146     // publish objectness
00147     pub_objectness_.publish(
00148       cv_bridge::CvImage(
00149         img_msg->header,
00150         sensor_msgs::image_encodings::TYPE_32FC1,
00151         objectness_img).toImageMsg());
00152   }
00153 
00154 }  // namespace jsk_perception
00155 
00156 #include <pluginlib/class_list_macros.h>
00157 PLUGINLIB_EXPORT_CLASS(jsk_perception::Bing, nodelet::Nodelet);


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