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/or 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 #include <jsk_topic_tools/log_utils.h>
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);
51  onInitPostProcess();
52  }
53 
55  // message_filters::Synchronizer needs to be called reset
56  // before message_filters::Subscriber is freed.
57  // Calling reset fixes the following error on shutdown of the nodelet:
58  // terminate called after throwing an instance of
59  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
60  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
61  // Also see https://github.com/ros/ros_comm/issues/720 .
62  sync_.reset();
63  async_.reset();
64  }
65 
67  {
68  sub_image_.subscribe(*pnh_, "input/image", 1);
69  sub_rects_.subscribe(*pnh_, "input/rect_array", 1);
70  if (approximate_sync_) {
71  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
72  async_->connectInput(sub_image_, sub_rects_);
73  async_->registerCallback(boost::bind(&RectArrayToDensityImage::convert, this, _1, _2));
74  }
75  else {
76  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
77  sync_->connectInput(sub_image_, sub_rects_);
78  sync_->registerCallback(boost::bind(&RectArrayToDensityImage::convert, this, _1, _2));
79  }
80  ros::V_string names = boost::assign::list_of("~input/image")("~input/rect_array");
81  jsk_topic_tools::warnNoRemap(names);
82  }
83 
85  {
88  }
89 
91  const sensor_msgs::Image::ConstPtr& image_msg,
92  const jsk_recognition_msgs::RectArray::ConstPtr& rects_msg)
93  {
94  vital_checker_->poke();
95  cv::Mat density_image = cv::Mat::zeros(image_msg->height, image_msg->width, CV_32FC1);
96 
97  // Compute density
98  for (size_t k=0; k<rects_msg->rects.size(); k++) {
99  jsk_recognition_msgs::Rect rect = rects_msg->rects[k];
100  for (int j=rect.y; j<(rect.y + rect.height); j++) {
101  for (int i=rect.x; i<(rect.x + rect.width); i++) {
102  density_image.at<float>(j, i)++;
103  }
104  }
105  }
106 
107  // Scale the density image value to [0, 1]
108  double min_image_value;
109  double max_image_value;
110  cv::minMaxLoc(density_image, &min_image_value, &max_image_value);
111  cv::Mat(density_image - min_image_value).convertTo(
112  density_image, CV_32FC1, 1. / (max_image_value - min_image_value));
113 
115  image_msg->header,
116  "32FC1",
117  density_image).toImageMsg());
118  }
119 }
120 
jsk_perception::RectArrayToDensityImage::~RectArrayToDensityImage
virtual ~RectArrayToDensityImage()
Definition: rect_array_to_density_image.cpp:86
jsk_perception::RectArrayToDensityImage::subscribe
virtual void subscribe()
Definition: rect_array_to_density_image.cpp:98
image_encodings.h
i
int i
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
jsk_perception::RectArrayToDensityImage::sub_rects_
message_filters::Subscriber< jsk_recognition_msgs::RectArray > sub_rects_
Definition: rect_array_to_density_image.h:137
jsk_perception::RectArrayToDensityImage::onInit
virtual void onInit()
Definition: rect_array_to_density_image.cpp:77
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_perception::RectArrayToDensityImage::unsubscribe
virtual void unsubscribe()
Definition: rect_array_to_density_image.cpp:116
class_list_macros.h
jsk_perception
Definition: add_mask_image.h:48
k
int k
jsk_perception::RectArrayToDensityImage::convert
virtual void convert(const sensor_msgs::Image::ConstPtr &image_msg, const jsk_recognition_msgs::RectArray::ConstPtr &rects_msg)
Definition: rect_array_to_density_image.cpp:122
jsk_perception::RectArrayToDensityImage::sub_image_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
Definition: rect_array_to_density_image.h:136
jsk_perception::RectArrayToDensityImage::pub_
ros::Publisher pub_
Definition: rect_array_to_density_image.h:138
jsk_perception::RectArrayToDensityImage::approximate_sync_
bool approximate_sync_
Definition: rect_array_to_density_image.h:132
jsk_perception::RectArrayToDensityImage
Definition: rect_array_to_density_image.h:82
message_filters::Subscriber::subscribe
void subscribe()
nodelet::Nodelet
rect_array_to_density_image.h
cv_bridge.h
cv_bridge::CvImage
ros::V_string
std::vector< std::string > V_string
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_perception::RectArrayToDensityImage, nodelet::Nodelet)
jsk_perception::RectArrayToDensityImage::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: rect_array_to_density_image.h:134
jsk_perception::RectArrayToDensityImage::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: rect_array_to_density_image.h:135
jsk_perception::RectArrayToDensityImage::queue_size_
int queue_size_
Definition: rect_array_to_density_image.h:133


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17