38 #ifndef JSK_PCL_ROS_ROI_CLIPPER_H_ 39 #define JSK_PCL_ROS_ROI_CLIPPER_H_ 45 #include <sensor_msgs/Image.h> 46 #include <sensor_msgs/CameraInfo.h> 47 #include <sensor_msgs/PointCloud2.h> 61 virtual void clip(
const sensor_msgs::Image::ConstPtr& image_msg,
62 const sensor_msgs::CameraInfo::ConstPtr& camera_info_msg);
66 const sensor_msgs::Image::ConstPtr& image_msg);
68 const sensor_msgs::CameraInfo::ConstPtr&
info_msg);
70 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
sensor_msgs::CameraInfo::ConstPtr latest_camera_info_
virtual void infoCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
ros::Publisher pub_image_
virtual void imageCallback(const sensor_msgs::Image::ConstPtr &image_msg)
ros::Subscriber sub_image_no_sync_
ros::Publisher pub_cloud_indices_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
virtual void clip(const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::CameraInfo::ConstPtr &camera_info_msg)
boost::mutex mutex
global mutex.
ros::Subscriber sub_cloud_no_sync_
ros::Publisher pub_cloud_
virtual void unsubscribe()
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
ros::Subscriber sub_info_no_sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_