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.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
00106 if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
00107
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);