Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef JSK_PCL_ROS_COLOR_BASED_REGION_GROWING_SEGMENTATION_H_
00037 #define JSK_PCL_ROS_COLOR_BASED_REGION_GROWING_SEGMENTATION_H_
00038
00039 #include <pcl_ros/pcl_nodelet.h>
00040 #include <pcl/point_types.h>
00041 #include <pcl/io/pcd_io.h>
00042 #include <pcl/search/search.h>
00043 #include <pcl/search/kdtree.h>
00044 #include <pcl/features/normal_3d.h>
00045 #include <pcl/filters/passthrough.h>
00046 #include <pcl/segmentation/region_growing_rgb.h>
00047
00048 #include <dynamic_reconfigure/server.h>
00049 #include "jsk_pcl_ros/ColorBasedRegionGrowingSegmentationConfig.h"
00050 #include <jsk_topic_tools/connection_based_nodelet.h>
00051 namespace jsk_pcl_ros
00052 {
00053 class ColorBasedRegionGrowingSegmentation:
00054 public jsk_topic_tools::ConnectionBasedNodelet
00055 {
00056 public:
00057 protected:
00058 ros::Publisher pub_;
00059 ros::Subscriber sub_;
00060 int distance_threshold_;
00061 int point_color_threshold_;
00062 int region_color_threshold_;
00063 int min_cluster_size_;
00064 typedef jsk_pcl_ros::ColorBasedRegionGrowingSegmentationConfig Config;
00065 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00066 boost::mutex mutex_;
00067 virtual void segment(const sensor_msgs::PointCloud2::ConstPtr& msg);
00068 virtual void configCallback (Config &config, uint32_t level);
00069 virtual void subscribe();
00070 virtual void unsubscribe();
00071 private:
00072 virtual void onInit();
00073 };
00074 }
00075
00076 #endif