point_indices_to_mask_image_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, 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 #define BOOST_PARAMETER_MAX_ARITY 7
39 #include <cv_bridge/cv_bridge.h>
40 
41 namespace jsk_pcl_ros_utils
42 {
44  {
45  DiagnosticNodelet::onInit();
46  pnh_->param("approximate_sync", approximate_sync_, false);
47  pnh_->param("queue_size", queue_size_, 100);
48  pnh_->param("static_image_size", static_image_size_, false);
49  pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
51  }
52 
54  {
55  if (static_image_size_) {
56  pnh_->getParam("width", width_);
57  pnh_->getParam("height", height_);
58  sub_input_static_ = pnh_->subscribe("input", 1, &PointIndicesToMaskImage::mask, this);
59  }
60  else {
61  sub_input_.subscribe(*pnh_, "input", 1);
62  sub_image_.subscribe(*pnh_, "input/image", 1);
63  if (approximate_sync_) {
64  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
65  async_->connectInput(sub_input_, sub_image_);
66  async_->registerCallback(boost::bind(&PointIndicesToMaskImage::mask, this, _1, _2));
67  }
68  else {
69  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
70  sync_->connectInput(sub_input_, sub_image_);
71  sync_->registerCallback(boost::bind(&PointIndicesToMaskImage::mask,
72  this, _1, _2));
73  }
74  }
75  }
76 
78  {
80  if (!static_image_size_) {
82  }
83  }
84 
86  const PCLIndicesMsg::ConstPtr& indices_msg,
87  const int width,
88  const int height)
89  {
90  cv::Mat mask_image = cv::Mat::zeros(height, width, CV_8UC1);
91  for (size_t i = 0; i < indices_msg->indices.size(); i++) {
92  int index = indices_msg->indices[i];
93  if (index >= height * width || index < 0) {
94  ROS_ERROR("Input index is out of expected mask size.");
95  return;
96  }
97  int width_index = index % width;
98  int height_index = index / width;
99  mask_image.at<uchar>(height_index, width_index) = 255;
100  }
101  cv_bridge::CvImage mask_bridge(indices_msg->header,
103  mask_image);
104  pub_.publish(mask_bridge.toImageMsg());
105  }
106 
108  const PCLIndicesMsg::ConstPtr& indices_msg)
109  {
110  vital_checker_->poke();
111  convertAndPublish(indices_msg, width_, height_);
112  }
113 
115  const PCLIndicesMsg::ConstPtr& indices_msg,
116  const sensor_msgs::Image::ConstPtr& image_msg)
117  {
118  vital_checker_->poke();
119  convertAndPublish(indices_msg, image_msg->width, image_msg->height);
120  }
121 }
122 
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PointIndicesToMaskImage, nodelet::Nodelet)
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void publish(const boost::shared_ptr< M > &message) const
virtual void convertAndPublish(const PCLIndicesMsg::ConstPtr &indices_msg, const int width, const int height)
message_filters::Subscriber< sensor_msgs::Image > sub_image_
unsigned int index
boost::shared_ptr< ros::NodeHandle > pnh_
message_filters::Subscriber< PCLIndicesMsg > sub_input_
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)
#define ROS_ERROR(...)
virtual void mask(const PCLIndicesMsg::ConstPtr &indices_msg)


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15