mask_image_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 
43 namespace jsk_pcl_ros
44 {
46  {
47  DiagnosticNodelet::onInit();
48  pnh_->param("negative", negative_, false);
49  pub_ = advertise<PCLIndicesMsg>(
50  *pnh_, "output", 1);
51  DiagnosticNodelet::onInitPostProcess();
52  }
53 
55  {
56  sub_cloud_ = pnh_->subscribe("input", 1, &MaskImageFilter::filter, this);
57  sub_image_ = pnh_->subscribe("input/mask", 1,
59  sub_info_ = pnh_->subscribe("input/camera_info", 1,
61  }
62 
64  {
68  }
69 
71  const sensor_msgs::CameraInfo::ConstPtr& info_ms)
72  {
73  boost::mutex::scoped_lock lock(mutex_);
74  camera_info_ = info_ms;
75  }
76 
78  const sensor_msgs::Image::ConstPtr& mask_msg)
79  {
80  boost::mutex::scoped_lock lock(mutex_);
83  mask_image_ = cv_ptr->image;
84 
85  if (negative_) {
86  cv::bitwise_not(mask_image_, mask_image_);
87  }
88  }
89 
91  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
92  {
93  boost::mutex::scoped_lock lock(mutex_);
94  if (camera_info_ && !mask_image_.empty()) {
97  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
98  (new pcl::PointCloud<pcl::PointXYZ>);
99  pcl::fromROSMsg(*cloud_msg, *cloud);
100  PCLIndicesMsg indices;
101  indices.header = cloud_msg->header;
102  for (size_t i = 0; i < cloud->points.size(); i++) {
103  pcl::PointXYZ p = cloud->points[i];
104  cv::Point2d uv = model.project3dToPixel(cv::Point3d(p.x, p.y, p.z));
105  // check size
106  if (uv.x > 0 && uv.x < mask_image_.cols &&
107  uv.y > 0 && uv.y < mask_image_.rows) {
108  if (mask_image_.at<uchar>(uv.y, uv.x) == 255) {
109  indices.indices.push_back(i);
110  }
111  }
112  }
113  pub_.publish(indices);
114  }
115  }
116 }
117 
120 
121 
virtual void infoCalback(const sensor_msgs::CameraInfo::ConstPtr &info_ms)
void publish(const boost::shared_ptr< M > &message) const
sensor_msgs::CameraInfo::ConstPtr camera_info_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
boost::shared_ptr< ros::NodeHandle > pnh_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::MaskImageFilter, nodelet::Nodelet)
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
virtual void imageCalback(const sensor_msgs::Image::ConstPtr &mask_msg)
p
cv::Point2d project3dToPixel(const cv::Point3d &xyz) const
pcl::PointIndices PCLIndicesMsg
cloud


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