add_color_from_image_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 
00038 #include "jsk_pcl_ros/add_color_from_image.h"
00039 #include <image_geometry/pinhole_camera_model.h>
00040 #include <cv_bridge/cv_bridge.h>
00041 #include <sensor_msgs/image_encodings.h>
00042 #include <pcl_conversions/pcl_conversions.h>
00043 
00044 namespace jsk_pcl_ros
00045 {
00046   void AddColorFromImage::onInit()
00047   {
00048     DiagnosticNodelet::onInit();
00049     pub_ = advertise<sensor_msgs::PointCloud2>(
00050       *pnh_, "output", 1);
00051     onInitPostProcess();
00052   }
00053 
00054   void AddColorFromImage::subscribe()
00055   {
00056     sub_cloud_.subscribe(*pnh_, "input", 1);
00057     sub_image_.subscribe(*pnh_, "input/image", 1);
00058     sub_info_.subscribe(*pnh_, "input/camera_info", 1);
00059     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00060     sync_->connectInput(sub_cloud_, sub_image_, sub_info_);
00061     sync_->registerCallback(boost::bind(&AddColorFromImage::addColor,
00062                                         this, _1, _2, _3));
00063   }
00064 
00065   void AddColorFromImage::unsubscribe()
00066   {
00067     sub_cloud_.unsubscribe();
00068     sub_info_.unsubscribe();
00069     sub_image_.unsubscribe();
00070   }
00071   
00072   void AddColorFromImage::addColor(
00073     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00074     const sensor_msgs::Image::ConstPtr& image_msg,
00075     const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00076   {
00077     if ((cloud_msg->header.frame_id != image_msg->header.frame_id) ||
00078         (cloud_msg->header.frame_id != info_msg->header.frame_id)) {
00079       NODELET_FATAL("frame_id is not collect: [%s, %s, %s",
00080                     cloud_msg->header.frame_id.c_str(),
00081                     image_msg->header.frame_id.c_str(),
00082                     info_msg->header.frame_id.c_str());
00083       return;
00084     }
00085     vital_checker_->poke();
00086     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
00087       (new pcl::PointCloud<pcl::PointXYZ>);
00088     pcl::fromROSMsg(*cloud_msg, *cloud);
00089     
00090     pcl::PointCloud<pcl::PointXYZRGB>::Ptr rgb_cloud
00091       (new pcl::PointCloud<pcl::PointXYZRGB>);
00092     rgb_cloud->points.resize(cloud->points.size());
00093     rgb_cloud->is_dense = cloud->is_dense;
00094     rgb_cloud->width = cloud->width;
00095     rgb_cloud->height = cloud->height;
00096     cv::Mat image = cv_bridge::toCvCopy(
00097       image_msg, sensor_msgs::image_encodings::BGR8)->image;
00098     image_geometry::PinholeCameraModel model;
00099     model.fromCameraInfo(info_msg);
00100     for (size_t i = 0; i < cloud->points.size(); i++) {
00101       pcl::PointXYZRGB p;
00102       p.x = cloud->points[i].x;
00103       p.y = cloud->points[i].y;
00104       p.z = cloud->points[i].z;
00105       //p.getVector3fMap() = cloud->points[i].getVector3fMap();
00106       if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
00107       // compute RGB
00108         cv::Point2d uv = model.project3dToPixel(cv::Point3d(p.x, p.y, p.z));
00109         if (uv.x > 0 && uv.x < image_msg->width &&
00110             uv.y > 0 && uv.y < image_msg->height) {
00111           cv::Vec3b rgb = image.at<cv::Vec3b>(uv.y, uv.x);
00112           p.r = rgb[2];
00113           p.g = rgb[1];
00114           p.b = rgb[0];
00115         }
00116       }
00117       rgb_cloud->points[i] = p;
00118     }
00119     sensor_msgs::PointCloud2 ros_cloud;
00120     pcl::toROSMsg(*rgb_cloud, ros_cloud);
00121     ros_cloud.header = cloud_msg->header;
00122     pub_.publish(ros_cloud);
00123   }
00124 }
00125 
00126 #include <pluginlib/class_list_macros.h>
00127 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::AddColorFromImage, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:49