00001 #ifndef _pointcloud_to_image_h_ 00002 #define _pointcloud_to_image_h_ 00003 00004 #include <nodelet/nodelet.h> 00005 #include <ros/ros.h> 00006 00007 // [publisher subscriber headers] 00008 #include <sensor_msgs/Image.h> 00009 #include <sensor_msgs/PointCloud2.h> 00010 00011 #include <pcl/point_cloud.h> 00012 //#include <pcl_ros/point_cloud.h> 00013 00014 #include <pcl/io/pcd_io.h> 00015 #include <pcl/ModelCoefficients.h> 00016 #include <pcl/segmentation/sac_segmentation.h> 00017 #include <pcl/sample_consensus/method_types.h> 00018 #include <pcl/filters/project_inliers.h> 00019 00020 // opencv 00021 #include <opencv2/imgproc/imgproc.hpp> 00022 #include <opencv2/highgui/highgui.hpp> 00023 00024 // cvmat to rosmsg 00025 #include <cv_bridge/cv_bridge.h> 00026 #include <sensor_msgs/image_encodings.h> 00027 00028 00029 00030 namespace iri_clean_board 00031 { 00032 00037 class PointcloudToImage : public nodelet::Nodelet 00038 { 00039 private: 00040 // [publisher attributes] 00041 sensor_msgs::ImagePtr Image_msg_; 00042 ros::Publisher segmented_pointcloud_publisher_images_; 00043 00044 // [subscriber attributes] 00045 ros::Subscriber input_pointcloud_subscriber_; 00046 void input_pointcloud_callback(const sensor_msgs::PointCloud2::ConstPtr& msg); 00047 00048 // [service attributes] 00049 00050 // [client attributes] 00051 00052 // [action server attributes] 00053 00054 // [action client attributes] 00055 00056 // node parameters 00057 00058 00064 cv::Mat pointcloud_to_image(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud); 00065 00071 sensor_msgs::ImagePtr cvimage_to_rosimage(cv::Mat cvimage); 00072 00078 void pcCallback(const sensor_msgs::PointCloud2::ConstPtr& msg); 00079 00080 public: 00087 virtual void onInit(); 00088 00089 00090 }; 00091 00092 } 00093 00094 #endif