Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037
00038 #include "jsk_pcl_ros/add_color_from_image_to_organized.h"
00039 #include <cv_bridge/cv_bridge.h>
00040 #include <sensor_msgs/image_encodings.h>
00041 #include <pcl_conversions/pcl_conversions.h>
00042
00043 namespace jsk_pcl_ros
00044 {
00045 void AddColorFromImageToOrganized::onInit()
00046 {
00047 DiagnosticNodelet::onInit();
00048 pub_ = advertise<sensor_msgs::PointCloud2>(
00049 *pnh_, "output", 1);
00050 onInitPostProcess();
00051 }
00052
00053 void AddColorFromImageToOrganized::subscribe()
00054 {
00055 sub_cloud_.subscribe(*pnh_, "input", 1);
00056 sub_image_.subscribe(*pnh_, "input/image", 1);
00057 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00058 sync_->connectInput(sub_cloud_, sub_image_);
00059 sync_->registerCallback(boost::bind(&AddColorFromImageToOrganized::addColor, this, _1, _2));
00060 }
00061
00062 void AddColorFromImageToOrganized::unsubscribe()
00063 {
00064 sub_cloud_.unsubscribe();
00065 sub_image_.unsubscribe();
00066 }
00067
00068 void AddColorFromImageToOrganized::addColor(
00069 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00070 const sensor_msgs::Image::ConstPtr& image_msg)
00071 {
00072 vital_checker_->poke();
00073 if (cloud_msg->header.frame_id != image_msg->header.frame_id)
00074 {
00075 NODELET_FATAL("frame_id does not match: [%s, %s]",
00076 cloud_msg->header.frame_id.c_str(),
00077 image_msg->header.frame_id.c_str());
00078 return;
00079 }
00080 if (cloud_msg->height != image_msg->height || cloud_msg->width != image_msg->width)
00081 {
00082 NODELET_FATAL("Size of input cloud and image does not match.");
00083 return;
00084 }
00085
00086 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
00087 (new pcl::PointCloud<pcl::PointXYZ>);
00088 pcl::fromROSMsg(*cloud_msg, *cloud);
00089
00090 cv::Mat image = cv_bridge::toCvCopy(
00091 image_msg, sensor_msgs::image_encodings::BGR8)->image;
00092
00093 pcl::PointCloud<pcl::PointXYZRGB>::Ptr rgb_cloud
00094 (new pcl::PointCloud<pcl::PointXYZRGB>);
00095 rgb_cloud->points.resize(cloud->points.size());
00096 rgb_cloud->is_dense = cloud->is_dense;
00097 rgb_cloud->width = cloud->width;
00098 rgb_cloud->height = cloud->height;
00099 for (size_t j=0; j<cloud->height; j++)
00100 {
00101 for (size_t i=0; i<cloud->width; i++)
00102 {
00103 pcl::PointXYZ p_xyz = cloud->points[i + j * cloud->width];
00104 pcl::PointXYZRGB p_color;
00105 p_color.x = p_xyz.x;
00106 p_color.y = p_xyz.y;
00107 p_color.z = p_xyz.z;
00108 cv::Vec3b bgr = image.at<cv::Vec3b>(j, i);
00109 p_color.b = bgr[0];
00110 p_color.g = bgr[1];
00111 p_color.r = bgr[2];
00112 rgb_cloud->points[i + j * cloud->width] = p_color;
00113 }
00114 }
00115 sensor_msgs::PointCloud2 ros_cloud;
00116 pcl::toROSMsg(*rgb_cloud, ros_cloud);
00117 ros_cloud.header = cloud_msg->header;
00118 pub_.publish(ros_cloud);
00119 }
00120 }
00121
00122 #include <pluginlib/class_list_macros.h>
00123 PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::AddColorFromImageToOrganized, nodelet::Nodelet);