mask_image_cluster_filter_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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 #define BOOST_PARAMETER_MAX_ARITY 7
38 #include <cv_bridge/cv_bridge.h>
42 #include <pcl/filters/extract_indices.h>
43 
44 
45 namespace jsk_pcl_ros
46 {
48  {
49  DiagnosticNodelet::onInit();
50  pub_ = advertise<PCLIndicesMsg>(
51  *pnh_, "output", 1);
53  }
54 
56  {
57  sub_image_ = pnh_->subscribe("input/mask", 1,
59  sub_info_ = pnh_->subscribe("input/camera_info", 1,
61  sub_input_.subscribe(*pnh_, "input", 1);
62  sub_target_.subscribe(*pnh_, "target", 1);
63  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
64  sync_->connectInput(sub_input_, sub_target_);
65  sync_->registerCallback(boost::bind(&MaskImageClusterFilter::concat, this, _1, _2));
66  }
67 
69  {
74  }
75 
77  const sensor_msgs::CameraInfo::ConstPtr& info_ms)
78  {
79  boost::mutex::scoped_lock lock(mutex_);
80  camera_info_ = info_ms;
81  }
82 
84  const sensor_msgs::Image::ConstPtr& mask_msg)
85  {
86  boost::mutex::scoped_lock lock(mutex_);
89  mask_image_ = cv_ptr->image;
90  }
91 
93  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
94  const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
95  {
96  boost::mutex::scoped_lock lock(mutex_);
97  if (camera_info_ && !mask_image_.empty()) {
100  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud
101  (new pcl::PointCloud<pcl::PointXYZRGB>);
102  pcl::fromROSMsg(*cloud_msg, *cloud);
103  PCLIndicesMsg indices;
104  indices.header = cloud_msg->header;
105  pcl::ExtractIndices<pcl::PointXYZRGB> extract;
106  extract.setInputCloud(cloud);
107  for (size_t i = 0; i < indices_input->cluster_indices.size(); i++) {
108  pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
109  pcl::IndicesPtr vindices;
110  vindices.reset (new std::vector<int> (indices_input->cluster_indices[i].indices));
111  extract.setIndices(vindices);
112  extract.filter(*segmented_cloud);
113  bool in_mask = false;
114  for (size_t j = 0; j < segmented_cloud->points.size(); j++) {
115  pcl::PointXYZRGB p = segmented_cloud->points[j];
116  cv::Point2d uv = model.project3dToPixel(cv::Point3d(p.x, p.y, p.z));
117  // check size
118  if (uv.x > 0 && uv.x < mask_image_.cols &&
119  uv.y > 0 && uv.y < mask_image_.rows) {
120  if (mask_image_.at<uchar>(uv.y, uv.x) == 255) {
121  in_mask = true;
122  break;
123  }
124  }
125  }
126  if (in_mask) {
127  vindices->size();
128  for(size_t j=0; j < vindices->size(); j++)
129  {
130  indices.indices.push_back((*vindices)[j]);
131  }
132  }
133  }
134  pub_.publish(indices);
135  }
136  }
137 }
138 
141 
142 
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::MaskImageClusterFilter, nodelet::Nodelet)
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void concat(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
boost::shared_ptr< ros::NodeHandle > pnh_
virtual void imageCalback(const sensor_msgs::Image::ConstPtr &mask_msg)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
sensor_msgs::CameraInfo::ConstPtr camera_info_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
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)
virtual void infoCalback(const sensor_msgs::CameraInfo::ConstPtr &info_ms)
p
cv::Point2d project3dToPixel(const cv::Point3d &xyz) const
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_target_
pcl::PointIndices PCLIndicesMsg
cloud


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47