37 #ifndef JSK_PCL_ROS_UTILS_MASK_IMAGE_TO_DEPTH_CONSIDERED_MASK_IMAGE_H_ 38 #define JSK_PCL_ROS_UTILS_MASK_IMAGE_TO_DEPTH_CONSIDERED_MASK_IMAGE_H_ 41 #include <sensor_msgs/Image.h> 42 #include <dynamic_reconfigure/server.h> 48 #include <jsk_pcl_ros_utils/MaskImageToDepthConsideredMaskImageConfig.h> 56 sensor_msgs::PointCloud2,
59 sensor_msgs::PointCloud2,
61 typedef jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImageConfig
Config;
73 const sensor_msgs::PointCloud2::ConstPtr& point_cloud2_msg,
74 const sensor_msgs::Image::ConstPtr& image_msg);
double region_x_off_ratio_
jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImageConfig Config
virtual void mask_region_callback(const sensor_msgs::Image::ConstPtr &msg)
virtual void configCallback(Config &config, uint32_t level)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::Image > ApproximateSyncPolicy
double region_width_ratio_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::Image > SyncPolicy
virtual void unsubscribe()
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
MaskImageToDepthConsideredMaskImage()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
bool in_the_order_of_depth_
double region_y_off_ratio_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
double region_height_ratio_
virtual void extractmask(const sensor_msgs::PointCloud2::ConstPtr &point_cloud2_msg, const sensor_msgs::Image::ConstPtr &image_msg)