mask_image_to_point_indices_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
38 #include <cv_bridge/cv_bridge.h>
40 
41 namespace jsk_pcl_ros_utils
42 {
44  {
45  DiagnosticNodelet::onInit();
46  pnh_->param("use_multi_channels", use_multi_channels_, false);
47  pnh_->param("target_channel", target_channel_, -1);
48 
50  pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output/all_indices", 1);
51  } else {
52  pub_ = advertise<PCLIndicesMsg>(*pnh_, "output", 1);
53  }
55  }
56 
58  {
59  sub_ = pnh_->subscribe("input", 1,
61  this);
62  }
63 
65  {
66  sub_.shutdown();
67  }
68 
70  const sensor_msgs::Image::ConstPtr& image_msg)
71  {
72  vital_checker_->poke();
73  if (use_multi_channels_) {
75  cv::Mat image = cv_ptr->image;
76  if (target_channel_ < 0) {
77  jsk_recognition_msgs::ClusterPointIndices cluster_msg;
78  cluster_msg.header = image_msg->header;
79  cluster_msg.cluster_indices.resize(image.channels());
80  for (size_t c = 0; c < image.channels(); ++c) {
81  PCLIndicesMsg &indices_msg = cluster_msg.cluster_indices[c];
82  indices_msg.header = image_msg->header;
83  for (size_t j = 0; j < image.rows; j++) {
84  for (size_t i = 0; i < image.cols; i++) {
85  if (image.data[j * image.step + i * image.elemSize() + c] > 127) {
86  indices_msg.indices.push_back(j * image.cols + i);
87  }
88  }
89  }
90  }
91  pub_.publish(cluster_msg);
92  } else {
93  if (target_channel_ > image.channels() - 1) {
94  NODELET_ERROR("target_channel_ is %d, but image has %d channels",
95  target_channel_, image.channels());
96  return;
97  }
98  PCLIndicesMsg indices_msg;
99  indices_msg.header = image_msg->header;
100  for (size_t j = 0; j < image.rows; j++) {
101  for (size_t i = 0; i < image.cols; i++) {
102  if (image.data[j * image.step + i * image.elemSize() + target_channel_] > 127) {
103  indices_msg.indices.push_back(j * image.cols + i);
104  }
105  }
106  }
107  pub_.publish(indices_msg);
108  }
109  } else {
112  cv::Mat image = cv_ptr->image;
113  PCLIndicesMsg indices_msg;
114  indices_msg.header = image_msg->header;
115  for (size_t j = 0; j < image.rows; j++) {
116  for (size_t i = 0; i < image.cols; i++) {
117  if (image.at<uchar>(j, i) > 127) {
118  indices_msg.indices.push_back(j * image.cols + i);
119  }
120  }
121  }
122  pub_.publish(indices_msg);
123  }
124  }
125 }
126 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
const std::string TYPE_8UC1
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::MaskImageToPointIndices, nodelet::Nodelet)
boost::shared_ptr< ros::NodeHandle > pnh_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
jsk_topic_tools::VitalChecker::Ptr vital_checker_
c
pcl::PointIndices PCLIndicesMsg
virtual void indices(const sensor_msgs::Image::ConstPtr &image_msg)


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