37 #ifndef JSK_PCL_ROS_ADD_COLOR_FROM_IMAGE_H_ 38 #define JSK_PCL_ROS_ADD_COLOR_FROM_IMAGE_H_ 47 #include <sensor_msgs/PointCloud2.h> 48 #include <sensor_msgs/Image.h> 49 #include <sensor_msgs/CameraInfo.h> 57 sensor_msgs::PointCloud2,
59 sensor_msgs::CameraInfo
67 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
68 const sensor_msgs::Image::ConstPtr& image_msg,
69 const sensor_msgs::CameraInfo::ConstPtr&
info_msg);
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void unsubscribe()
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
message_filters::Subscriber< sensor_msgs::Image > sub_image_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
virtual void addColor(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::CameraInfo::ConstPtr &info_msg)
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_