rect_array_to_density_image.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 
37 #include <boost/assign.hpp>
40 #include <opencv2/opencv.hpp>
41 #include <cv_bridge/cv_bridge.h>
42 
43 namespace jsk_perception
44 {
46  {
47  DiagnosticNodelet::onInit();
48  pnh_->param("approximate_sync", approximate_sync_, false);
49  pnh_->param("queue_size", queue_size_, 100);
50  pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
52  }
53 
55  {
56  sub_image_.subscribe(*pnh_, "input/image", 1);
57  sub_rects_.subscribe(*pnh_, "input/rect_array", 1);
58  if (approximate_sync_) {
59  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
60  async_->connectInput(sub_image_, sub_rects_);
61  async_->registerCallback(boost::bind(&RectArrayToDensityImage::convert, this, _1, _2));
62  }
63  else {
64  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
65  sync_->connectInput(sub_image_, sub_rects_);
66  sync_->registerCallback(boost::bind(&RectArrayToDensityImage::convert, this, _1, _2));
67  }
68  ros::V_string names = boost::assign::list_of("~input/image")("~input/rect_array");
70  }
71 
73  {
76  }
77 
79  const sensor_msgs::Image::ConstPtr& image_msg,
80  const jsk_recognition_msgs::RectArray::ConstPtr& rects_msg)
81  {
82  vital_checker_->poke();
83  cv::Mat density_image = cv::Mat::zeros(image_msg->height, image_msg->width, CV_32FC1);
84 
85  // Compute density
86  for (size_t k=0; k<rects_msg->rects.size(); k++) {
87  jsk_recognition_msgs::Rect rect = rects_msg->rects[k];
88  for (int j=rect.y; j<(rect.y + rect.height); j++) {
89  for (int i=rect.x; i<(rect.x + rect.width); i++) {
90  density_image.at<float>(j, i)++;
91  }
92  }
93  }
94 
95  // Scale the density image value to [0, 1]
96  double min_image_value;
97  double max_image_value;
98  cv::minMaxLoc(density_image, &min_image_value, &max_image_value);
99  cv::Mat(density_image - min_image_value).convertTo(
100  density_image, CV_32FC1, 1. / (max_image_value - min_image_value));
101 
103  image_msg->header,
104  "32FC1",
105  density_image).toImageMsg());
106  }
107 }
108 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void publish(const boost::shared_ptr< M > &message) const
virtual void convert(const sensor_msgs::Image::ConstPtr &image_msg, const jsk_recognition_msgs::RectArray::ConstPtr &rects_msg)
PLUGINLIB_EXPORT_CLASS(jsk_perception::RectArrayToDensityImage, nodelet::Nodelet)
message_filters::Subscriber< sensor_msgs::Image > sub_image_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
std::vector< std::string > V_string
boost::shared_ptr< ros::NodeHandle > pnh_
bool warnNoRemap(const std::vector< std::string > names)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
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)
sensor_msgs::ImagePtr toImageMsg() const
message_filters::Subscriber< jsk_recognition_msgs::RectArray > sub_rects_


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