bing.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016, 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 
36 #include "jsk_perception/bing.h"
37 #include <ros/ros.h>
38 #include <rospack/rospack.h>
39 #include <boost/assign.hpp>
40 #include <boost/filesystem.hpp>
43 #include <jsk_recognition_msgs/RectArray.h>
44 #include <cv_bridge/cv_bridge.h>
45 #include <opencv2/opencv.hpp>
46 #include <opencv2/saliency.hpp>
47 #include <vector>
48 #include <algorithm>
49 
50 namespace jsk_perception
51 {
52  void Bing::onInit()
53  {
54  DiagnosticNodelet::onInit();
55  pub_rects_ = advertise<jsk_recognition_msgs::RectArray>(*pnh_, "output", 1);
56  pub_objectness_ = advertise<sensor_msgs::Image>(*pnh_, "output/objectness", 1);
57  // find trained data
58  std::string training_path;
59 #ifdef ROSPACK_EXPORT
61  rospack::Package *p = rp.get_pkg("jsk_perception");
62  if (p == NULL) {
63  ROS_ERROR("Package path of 'jsk_perception' does not found");
64  exit(1);
65  } else {
66  training_path = p->path + std::string("/trained_data/ObjectnessTrainedModel");
67  }
68 #else
70  ros::V_string search_path;
71  rp.getSearchPathFromEnv(search_path);
72  rp.crawl(search_path, 1);
73  std::string path;
74  if (rp.find("jsk_perception", path) == true) {
75  training_path = path + std::string("/trained_data/ObjectnessTrainedModel");
76  } else {
77  ROS_ERROR("Package path of 'jsk_perception' does not found");
78  exit(1);
79  }
80 #endif
81  if (!boost::filesystem::exists(training_path)) {
82  ROS_ERROR("Training data path '%s' does not exist", training_path.c_str());
83  exit(1);
84  }
85  // setup bing
86  binger_ = new cv::saliency::ObjectnessBING();
87  binger_->setTrainingPath(training_path);
89  }
90 
92  {
93  sub_ = pnh_->subscribe("input", 1, &Bing::apply, this);
94  ros::V_string names = boost::assign::list_of("~input");
96  }
97 
99  {
100  sub_.shutdown();
101  }
102 
104  const sensor_msgs::Image::ConstPtr& img_msg)
105  {
107  img_msg, img_msg->encoding);
108  cv::Mat img = cv_ptr->image;
109 
110  // Resize too large image for fast processing
111  double scale = 1.0;
112  if (img.rows * img.cols > 250000) {
113  scale = static_cast<double>(std::min(500. / img.rows, 500. / img.cols));
114  cv::resize(img, img, cv::Size(static_cast<int>(scale * img.cols),
115  static_cast<int>(scale * img.rows)));
116  }
117 
118  std::vector<cv::Vec4i> saliency_map;
119  binger_->computeSaliency(img, saliency_map);
120  std::vector<float> objectness_values = binger_->getobjectnessValues();
121 
122  jsk_recognition_msgs::RectArray rects_msg;
123  cv::Mat objectness_img = cv::Mat(img.rows, img.cols, CV_32FC1);
124  for (size_t k=0; k < saliency_map.size(); k++) {
125  int min_x = static_cast<int>(saliency_map[k][0] / scale);
126  int min_y = static_cast<int>(saliency_map[k][1] / scale);
127  int max_x = static_cast<int>(saliency_map[k][2] / scale);
128  int max_y = static_cast<int>(saliency_map[k][3] / scale);
129  // set a proposal
130  jsk_recognition_msgs::Rect rect;
131  rect.x = min_x;
132  rect.y = min_y;
133  rect.width = max_x - min_x;
134  rect.height = max_y - min_y;
135  rects_msg.rects.push_back(rect);
136  // set objectness
137  for (size_t j=std::max(0, min_y); j < std::min(max_y, img.rows); j++) {
138  for (size_t i=std::max(0, min_x); i < std::min(max_x, img.cols); i++) {
139  objectness_img.at<float>(j, i) += objectness_values[k];
140  }
141  }
142  }
143  // publish proposals
144  rects_msg.header = img_msg->header;
145  pub_rects_.publish(rects_msg);
146  // publish objectness
149  img_msg->header,
151  objectness_img).toImageMsg());
152  }
153 
154 } // namespace jsk_perception
155 
rospack::Rospack rp
virtual void subscribe()
Definition: bing.cpp:91
ros::Publisher pub_rects_
Definition: bing.h:59
path
void publish(const boost::shared_ptr< M > &message) const
cv::saliency::ObjectnessBING * binger_
Definition: bing.h:61
virtual void onInit()
Definition: bing.cpp:52
std::vector< std::string > V_string
boost::shared_ptr< ros::NodeHandle > pnh_
const std::string TYPE_32FC1
bool warnNoRemap(const std::vector< std::string > names)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
ros::Subscriber sub_
Definition: bing.h:58
bool getSearchPathFromEnv(std::vector< std::string > &sp)
void crawl(std::vector< std::string > search_path, bool force)
ros::Publisher pub_objectness_
Definition: bing.h:60
#define NULL
bool find(const std::string &name, std::string &path)
virtual void apply(const sensor_msgs::Image::ConstPtr &image_msg)
Definition: bing.cpp:103
#define ROS_ERROR(...)
PLUGINLIB_EXPORT_CLASS(jsk_perception::Bing, nodelet::Nodelet)
sensor_msgs::ImagePtr toImageMsg() const
virtual void unsubscribe()
Definition: bing.cpp:98


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