36 #define BOOST_PARAMETER_MAX_ARITY 7 47 DiagnosticNodelet::onInit();
48 pub_ = advertise<sensor_msgs::PointCloud2>(
57 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
69 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
70 const sensor_msgs::Image::ConstPtr& image_msg)
73 if (cloud_msg->header.frame_id != image_msg->header.frame_id)
76 cloud_msg->header.frame_id.c_str(),
77 image_msg->header.frame_id.c_str());
80 if (cloud_msg->height != image_msg->height || cloud_msg->width != image_msg->width)
82 NODELET_FATAL(
"Size of input cloud and image does not match.");
86 pcl::PointCloud<pcl::PointXYZ>::Ptr
cloud 87 (
new pcl::PointCloud<pcl::PointXYZ>);
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++)
101 for (
size_t i=0; i<cloud->width; i++)
103 pcl::PointXYZ p_xyz = cloud->points[i + j * cloud->width];
104 pcl::PointXYZRGB p_color;
108 cv::Vec3b bgr = image.at<cv::Vec3b>(j, i);
112 rgb_cloud->points[i + j * cloud->width] = p_color;
115 sensor_msgs::PointCloud2 ros_cloud;
117 ros_cloud.header = cloud_msg->header;
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)
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)
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)
virtual void unsubscribe()
#define NODELET_FATAL(...)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_