#include <region_growing_segmentation.h>

| Protected Types | |
| typedef jsk_pcl_ros::RegionGrowingSegmentationConfig | Config | 
| Protected Member Functions | |
| virtual void | configCallback (Config &config, uint32_t level) | 
| virtual void | segment (const sensor_msgs::PointCloud2::ConstPtr &msg) | 
| virtual void | subscribe () | 
| virtual void | unsubscribe () | 
| Protected Attributes | |
| double | curvature_threshold_ | 
| int | max_size_ | 
| int | min_size_ | 
| boost::mutex | mutex_ | 
| int | number_of_neighbors_ | 
| ros::Publisher | pub_ | 
| double | smoothness_threshold_ | 
| boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ | 
| ros::Subscriber | sub_ | 
| Private Member Functions | |
| virtual void | onInit () | 
Definition at line 53 of file region_growing_segmentation.h.
| typedef jsk_pcl_ros::RegionGrowingSegmentationConfig jsk_pcl_ros::RegionGrowingSegmentation::Config  [protected] | 
Definition at line 65 of file region_growing_segmentation.h.
| void jsk_pcl_ros::RegionGrowingSegmentation::configCallback | ( | Config & | config, | 
| uint32_t | level | ||
| ) |  [protected, virtual] | 
Definition at line 68 of file region_growing_segmentation_nodelet.cpp.
| void jsk_pcl_ros::RegionGrowingSegmentation::onInit | ( | void | ) |  [private, virtual] | 
Definition at line 47 of file region_growing_segmentation_nodelet.cpp.
| void jsk_pcl_ros::RegionGrowingSegmentation::segment | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) |  [protected, virtual] | 
Definition at line 89 of file region_growing_segmentation_nodelet.cpp.
| void jsk_pcl_ros::RegionGrowingSegmentation::subscribe | ( | ) |  [protected, virtual] | 
Definition at line 58 of file region_growing_segmentation_nodelet.cpp.
| void jsk_pcl_ros::RegionGrowingSegmentation::unsubscribe | ( | ) |  [protected, virtual] | 
Definition at line 63 of file region_growing_segmentation_nodelet.cpp.
| double jsk_pcl_ros::RegionGrowingSegmentation::curvature_threshold_  [protected] | 
Definition at line 64 of file region_growing_segmentation.h.
| int jsk_pcl_ros::RegionGrowingSegmentation::max_size_  [protected] | 
Definition at line 62 of file region_growing_segmentation.h.
| int jsk_pcl_ros::RegionGrowingSegmentation::min_size_  [protected] | 
Definition at line 61 of file region_growing_segmentation.h.
Definition at line 67 of file region_growing_segmentation.h.
| int jsk_pcl_ros::RegionGrowingSegmentation::number_of_neighbors_  [protected] | 
Definition at line 60 of file region_growing_segmentation.h.
Definition at line 58 of file region_growing_segmentation.h.
| double jsk_pcl_ros::RegionGrowingSegmentation::smoothness_threshold_  [protected] | 
Definition at line 63 of file region_growing_segmentation.h.
| boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::RegionGrowingSegmentation::srv_  [protected] | 
Definition at line 66 of file region_growing_segmentation.h.
Definition at line 59 of file region_growing_segmentation.h.