add_color_from_image_to_organized_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2017, 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
37 
39 #include <cv_bridge/cv_bridge.h>
42 
43 namespace jsk_pcl_ros
44 {
46  {
47  DiagnosticNodelet::onInit();
48  pub_ = advertise<sensor_msgs::PointCloud2>(
49  *pnh_, "output", 1);
51  }
52 
54  {
55  sub_cloud_.subscribe(*pnh_, "input", 1);
56  sub_image_.subscribe(*pnh_, "input/image", 1);
57  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
58  sync_->connectInput(sub_cloud_, sub_image_);
59  sync_->registerCallback(boost::bind(&AddColorFromImageToOrganized::addColor, this, _1, _2));
60  }
61 
63  {
66  }
67 
69  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
70  const sensor_msgs::Image::ConstPtr& image_msg)
71  {
72  vital_checker_->poke();
73  if (cloud_msg->header.frame_id != image_msg->header.frame_id)
74  {
75  NODELET_FATAL("frame_id does not match: [%s, %s]",
76  cloud_msg->header.frame_id.c_str(),
77  image_msg->header.frame_id.c_str());
78  return;
79  }
80  if (cloud_msg->height != image_msg->height || cloud_msg->width != image_msg->width)
81  {
82  NODELET_FATAL("Size of input cloud and image does not match.");
83  return;
84  }
85 
86  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
87  (new pcl::PointCloud<pcl::PointXYZ>);
88  pcl::fromROSMsg(*cloud_msg, *cloud);
89 
90  cv::Mat image = cv_bridge::toCvCopy(
91  image_msg, sensor_msgs::image_encodings::BGR8)->image;
92 
93  pcl::PointCloud<pcl::PointXYZRGB>::Ptr rgb_cloud
94  (new pcl::PointCloud<pcl::PointXYZRGB>);
95  rgb_cloud->points.resize(cloud->points.size());
96  rgb_cloud->is_dense = cloud->is_dense;
97  rgb_cloud->width = cloud->width;
98  rgb_cloud->height = cloud->height;
99  for (size_t j=0; j<cloud->height; j++)
100  {
101  for (size_t i=0; i<cloud->width; i++)
102  {
103  pcl::PointXYZ p_xyz = cloud->points[i + j * cloud->width];
104  pcl::PointXYZRGB p_color;
105  p_color.x = p_xyz.x;
106  p_color.y = p_xyz.y;
107  p_color.z = p_xyz.z;
108  cv::Vec3b bgr = image.at<cv::Vec3b>(j, i);
109  p_color.b = bgr[0];
110  p_color.g = bgr[1];
111  p_color.r = bgr[2];
112  rgb_cloud->points[i + j * cloud->width] = p_color;
113  }
114  }
115  sensor_msgs::PointCloud2 ros_cloud;
116  pcl::toROSMsg(*rgb_cloud, ros_cloud);
117  ros_cloud.header = cloud_msg->header;
118  pub_.publish(ros_cloud);
119  }
120 }
121 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
message_filters::Subscriber< sensor_msgs::Image > sub_image_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::AddColorFromImageToOrganized, nodelet::Nodelet)
virtual void addColor(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::Image::ConstPtr &image_msg)
boost::shared_ptr< ros::NodeHandle > pnh_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
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 NODELET_FATAL(...)
cloud
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_


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