pointcloud_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) 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 #define BOOST_PARAMETER_MAX_ARITY 7
38 #include <cv_bridge/cv_bridge.h>
40 
42 
43 namespace jsk_pcl_ros_utils
44 {
46  {
47  DiagnosticNodelet::onInit();
48 
49  srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
50  typename dynamic_reconfigure::Server<Config>::CallbackType f =
51  boost::bind(&PointCloudToMaskImage::configCallback, this, _1, _2);
52  srv_->setCallback(f);
53 
54  pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
55  onInitPostProcess();
56  }
57 
59  {
60  sub_cloud_ = pnh_->subscribe<sensor_msgs::PointCloud2>(
61  "input", 1, &PointCloudToMaskImage::convert, this);
62  sub_image_ = pnh_->subscribe<sensor_msgs::Image>(
63  "input/depth", 1, &PointCloudToMaskImage::convert, this);
64  }
65 
67  {
70  }
71 
72  void PointCloudToMaskImage::configCallback(Config &config, uint32_t level)
73  {
74  boost::mutex::scoped_lock lock(mutex_);
75  z_near_ = std::min(config.z_near, config.z_far);
76  z_far_ = std::max(config.z_near, config.z_far);
77  config.z_near = z_near_;
78  config.z_far = z_far_;
79  }
80 
81  void PointCloudToMaskImage::convert(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
82  {
83  boost::mutex::scoped_lock lock(mutex_);
84 
85  vital_checker_->poke();
86  pcl::PointCloud<pcl::PointXYZ>::Ptr pc(new pcl::PointCloud<pcl::PointXYZ>);
87  pcl::fromROSMsg(*cloud_msg, *pc);
88 
89  if (!pc->isOrganized())
90  {
91  NODELET_FATAL("Input point cloud is not organized.");
92  return;
93  }
94 
95  cv::Mat mask_image = cv::Mat::zeros(cloud_msg->height, cloud_msg->width, CV_8UC1);
96  for (size_t index = 0; index < pc->points.size(); index++)
97  {
98  if (isnan(pc->points[index].x) || isnan(pc->points[index].y) || isnan(pc->points[index].z))
99  {
100  continue;
101  }
102  if (pc->points[index].z < z_near_ || pc->points[index].z > z_far_)
103  {
104  continue;
105  }
106  int width_index = index % cloud_msg->width;
107  int height_index = index / cloud_msg->width;
108  mask_image.at<uchar>(height_index, width_index) = 255;
109  }
110  cv_bridge::CvImage mask_bridge(cloud_msg->header,
112  mask_image);
113  pub_.publish(mask_bridge.toImageMsg());
114  }
115 
116  void PointCloudToMaskImage::convert(const sensor_msgs::Image::ConstPtr& image_msg)
117  {
118  boost::mutex::scoped_lock lock(mutex_);
119  vital_checker_->poke();
120 
121  cv_bridge::CvImage::Ptr depth_img;
122  try {
123  depth_img = cv_bridge::toCvCopy(image_msg);
124  } catch (cv_bridge::Exception &e) {
125  NODELET_ERROR_STREAM("Failed to convert image: " << e.what());
126  return;
127  }
128 
130  mask_img->header = depth_img->header;
131  mask_img->encoding = "mono8";
132  mask_img->image = cv::Mat(depth_img->image.rows, depth_img->image.cols, CV_8UC1);
133 
134  cv::MatIterator_<uint8_t>
135  mask_it = mask_img->image.begin<uint8_t>(),
136  mask_end = mask_img->image.end<uint8_t>();
137 
138  if (depth_img->encoding == enc::TYPE_32FC1) {
139  cv::MatConstIterator_<float>
140  depth_it = depth_img->image.begin<float>(),
141  depth_end = depth_img->image.end<float>();
142 
143  for (; (depth_it != depth_end) && (mask_it != mask_end); ++depth_it, ++mask_it)
144  {
145  if (z_near_ < *depth_it && *depth_it < z_far_) *mask_it = -1;
146  else *mask_it = 0;
147  }
148  } else if (depth_img->encoding == enc::TYPE_16UC1) {
149  uint16_t z_near16 = (uint16_t) (z_near_ * 1000.0), z_far16 = (uint16_t) (z_far_ * 1000.0); // mm
150  cv::MatConstIterator_<uint16_t>
151  depth_it = depth_img->image.begin<uint16_t>(),
152  depth_end = depth_img->image.end<uint16_t>();
153 
154  for (; (depth_it != depth_end) && (mask_it != mask_end); ++depth_it, ++mask_it)
155  {
156  if (z_near16 < *depth_it && *depth_it < z_far16) *mask_it = -1;
157  else *mask_it = 0;
158  }
159 
160  } else {
161  NODELET_ERROR_STREAM("Invalid encoding:" << depth_img->encoding);
162  return;
163  }
164 
165  pub_.publish(mask_img->toImageMsg());
166  }
167 }
168 
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
sensor_msgs::image_encodings
NODELET_FATAL
#define NODELET_FATAL(...)
_2
boost::arg< 2 > _2
image_encodings.h
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PointCloudToMaskImage, nodelet::Nodelet)
jsk_pcl_ros_utils::PointCloudToMaskImage
Definition: pointcloud_to_mask_image.h:83
boost::shared_ptr
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
lock
lock
jsk_pcl_ros_utils::PointCloudToMaskImage::pub_
ros::Publisher pub_
Definition: pointcloud_to_mask_image.h:139
ros::Subscriber::shutdown
void shutdown()
jsk_pcl_ros_utils::PointCloudToMaskImage::unsubscribe
virtual void unsubscribe()
Definition: pointcloud_to_mask_image_nodelet.cpp:66
cv_bridge::Exception
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_pcl_ros_utils::PointCloudToMaskImage::convert
virtual void convert(const sensor_msgs::Image::ConstPtr &image_msg)
Definition: pointcloud_to_mask_image_nodelet.cpp:116
jsk_pcl_ros_utils::PointCloudToMaskImage::mutex_
boost::mutex mutex_
Definition: pointcloud_to_mask_image.h:135
class_list_macros.h
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
NODELET_ERROR_STREAM
#define NODELET_ERROR_STREAM(...)
jsk_pcl_ros_utils::PointCloudToMaskImage::sub_image_
ros::Subscriber sub_image_
Definition: pointcloud_to_mask_image.h:138
pointcloud_to_mask_image.h
jsk_pcl_ros_utils::PointCloudToMaskImage::z_near_
float z_near_
Definition: pointcloud_to_mask_image.h:134
_1
boost::arg< 1 > _1
pcl_conversion_util.h
jsk_pcl_ros_utils::PointCloudToMaskImage::subscribe
virtual void subscribe()
Definition: pointcloud_to_mask_image_nodelet.cpp:58
f
f
nodelet::Nodelet
sensor_msgs::image_encodings::MONO8
const std::string MONO8
cv_bridge.h
jsk_pcl_ros_utils::PointCloudToMaskImage::onInit
virtual void onInit()
Definition: pointcloud_to_mask_image_nodelet.cpp:45
cv_bridge::CvImage
jsk_pcl_ros_utils::PointCloudToMaskImage::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: pointcloud_to_mask_image.h:136
jsk_pcl_ros_utils::PointCloudToMaskImage::sub_cloud_
ros::Subscriber sub_cloud_
Definition: pointcloud_to_mask_image.h:137
index
unsigned int index
jsk_pcl_ros_utils::PointCloudToMaskImage::z_far_
float z_far_
Definition: pointcloud_to_mask_image.h:134
jsk_pcl_ros_utils::PointCloudToMaskImage::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: pointcloud_to_mask_image_nodelet.cpp:72
config
config
jsk_pcl_ros_utils::PointCloudToMaskImage::Config
PointCloudToMaskImageConfig Config
Definition: pointcloud_to_mask_image.h:118


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43