add_color_from_image_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 
36 #define BOOST_PARAMETER_MAX_ARITY 7
37 
40 #include <cv_bridge/cv_bridge.h>
43 
44 namespace jsk_pcl_ros
45 {
47  {
48  DiagnosticNodelet::onInit();
49  pub_ = advertise<sensor_msgs::PointCloud2>(
50  *pnh_, "output", 1);
52  }
53 
55  {
56  sub_cloud_.subscribe(*pnh_, "input", 1);
57  sub_image_.subscribe(*pnh_, "input/image", 1);
58  sub_info_.subscribe(*pnh_, "input/camera_info", 1);
59  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
60  sync_->connectInput(sub_cloud_, sub_image_, sub_info_);
61  sync_->registerCallback(boost::bind(&AddColorFromImage::addColor,
62  this, _1, _2, _3));
63  }
64 
66  {
70  }
71 
73  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
74  const sensor_msgs::Image::ConstPtr& image_msg,
75  const sensor_msgs::CameraInfo::ConstPtr& info_msg)
76  {
77  if ((cloud_msg->header.frame_id != image_msg->header.frame_id) ||
78  (cloud_msg->header.frame_id != info_msg->header.frame_id)) {
79  NODELET_FATAL("frame_id is not collect: [%s, %s, %s",
80  cloud_msg->header.frame_id.c_str(),
81  image_msg->header.frame_id.c_str(),
82  info_msg->header.frame_id.c_str());
83  return;
84  }
85  vital_checker_->poke();
86  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
87  (new pcl::PointCloud<pcl::PointXYZ>);
88  pcl::fromROSMsg(*cloud_msg, *cloud);
89 
90  pcl::PointCloud<pcl::PointXYZRGB>::Ptr rgb_cloud
91  (new pcl::PointCloud<pcl::PointXYZRGB>);
92  rgb_cloud->points.resize(cloud->points.size());
93  rgb_cloud->is_dense = cloud->is_dense;
94  rgb_cloud->width = cloud->width;
95  rgb_cloud->height = cloud->height;
96  cv::Mat image = cv_bridge::toCvCopy(
97  image_msg, sensor_msgs::image_encodings::BGR8)->image;
99  model.fromCameraInfo(info_msg);
100  for (size_t i = 0; i < cloud->points.size(); i++) {
101  pcl::PointXYZRGB p;
102  p.x = cloud->points[i].x;
103  p.y = cloud->points[i].y;
104  p.z = cloud->points[i].z;
105  //p.getVector3fMap() = cloud->points[i].getVector3fMap();
106  if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
107  // compute RGB
108  cv::Point2d uv = model.project3dToPixel(cv::Point3d(p.x, p.y, p.z));
109  if (uv.x > 0 && uv.x < image_msg->width &&
110  uv.y > 0 && uv.y < image_msg->height) {
111  cv::Vec3b rgb = image.at<cv::Vec3b>(uv.y, uv.x);
112  p.r = rgb[2];
113  p.g = rgb[1];
114  p.b = rgb[0];
115  }
116  }
117  rgb_cloud->points[i] = p;
118  }
119  sensor_msgs::PointCloud2 ros_cloud;
120  pcl::toROSMsg(*rgb_cloud, ros_cloud);
121  ros_cloud.header = cloud_msg->header;
122  pub_.publish(ros_cloud);
123  }
124 }
125 
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::AddColorFromImage, nodelet::Nodelet)
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())
rgb
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)
message_filters::Subscriber< sensor_msgs::Image > sub_image_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
p
cv::Point2d project3dToPixel(const cv::Point3d &xyz) const
#define NODELET_FATAL(...)
virtual void addColor(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::CameraInfo::ConstPtr &info_msg)
cloud
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_


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