36 #ifndef JSK_PCL_ROS_COLOR_BASED_REGION_GROWING_SEGMENTATION_H_ 37 #define JSK_PCL_ROS_COLOR_BASED_REGION_GROWING_SEGMENTATION_H_ 40 #include <pcl/point_types.h> 41 #include <pcl/io/pcd_io.h> 42 #include <pcl/search/search.h> 43 #include <pcl/search/kdtree.h> 44 #include <pcl/features/normal_3d.h> 45 #include <pcl/filters/passthrough.h> 46 #include <pcl/segmentation/region_growing_rgb.h> 48 #include <dynamic_reconfigure/server.h> 49 #include "jsk_pcl_ros/ColorBasedRegionGrowingSegmentationConfig.h" 64 typedef jsk_pcl_ros::ColorBasedRegionGrowingSegmentationConfig
Config;
67 virtual void segment(
const sensor_msgs::PointCloud2::ConstPtr&
msg);
int region_color_threshold_
int point_color_threshold_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void unsubscribe()
jsk_pcl_ros::ColorBasedRegionGrowingSegmentationConfig Config
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &msg)
boost::mutex mutex
global mutex.
virtual void configCallback(Config &config, uint32_t level)