37 #ifndef JSK_PCL_ROS_UTILS_POINTCLOUD_TO_MASK_IMAGE_H_ 38 #define JSK_PCL_ROS_UTILS_POINTCLOUD_TO_MASK_IMAGE_H_ 40 #include <boost/shared_ptr.hpp> 42 #include <dynamic_reconfigure/server.h> 44 #include <sensor_msgs/Image.h> 45 #include <sensor_msgs/PointCloud2.h> 47 #include <jsk_pcl_ros_utils/PointCloudToMaskImageConfig.h> 54 typedef PointCloudToMaskImageConfig
Config;
64 virtual void convert(
const sensor_msgs::Image::ConstPtr& image_msg);
65 virtual void convert(
const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
81 #endif // JSK_PCL_ROS_UTILS_POINTCLOUD_TO_MASK_IMAGE_H_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void convert(const sensor_msgs::Image::ConstPtr &image_msg)
ros::Subscriber sub_image_
PointCloudToMaskImageConfig Config
ros::Subscriber sub_cloud_
virtual void unsubscribe()
virtual void configCallback(Config &config, uint32_t level)