#include <region_growing_multiple_plane_segmentation.h>
| Public Types | |
| typedef RegionGrowingMultiplePlaneSegmentationConfig | Config | 
| typedef message_filters::sync_policies::ExactTime < sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | NormalSyncPolicy | 
| typedef pcl::PointXYZRGB | PointT | 
| Public Member Functions | |
| RegionGrowingMultiplePlaneSegmentation () | |
| Protected Member Functions | |
| virtual void | configCallback (Config &config, uint32_t level) | 
| virtual void | onInit () | 
| virtual void | ransacEstimation (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointIndices::Ptr &indices, pcl::PointIndices &inliers, pcl::ModelCoefficients &coefficient) | 
| virtual void | segment (const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::PointCloud2::ConstPtr &normal_msg) | 
| virtual void | subscribe () | 
| virtual void | unsubscribe () | 
| Static Protected Member Functions | |
| static bool | regionGrowingFunction (const pcl::PointXYZRGBNormal &a, const pcl::PointXYZRGBNormal &b, float distance) | 
| static void | setCondifionFunctionParameter (const double angular_threshold, const double distance_threshold) | 
| Protected Attributes | |
| double | angular_threshold_ | 
| double | cluster_tolerance_ | 
| double | distance_threshold_ | 
| bool | done_initialization_ | 
| double | max_area_ | 
| double | max_curvature_ | 
| int | max_size_ | 
| double | min_area_ | 
| int | min_size_ | 
| boost::mutex | mutex_ | 
| ros::Publisher | pub_average_time_ | 
| ros::Publisher | pub_clustering_result_ | 
| ros::Publisher | pub_coefficients_ | 
| ros::Publisher | pub_inliers_ | 
| ros::Publisher | pub_latest_time_ | 
| ros::Publisher | pub_polygons_ | 
| int | ransac_refine_max_iterations_ | 
| double | ransac_refine_outlier_distance_threshold_ | 
| boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_input_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_normal_ | 
| boost::shared_ptr < message_filters::Synchronizer < NormalSyncPolicy > > | sync_ | 
| jsk_recognition_utils::WallDurationTimer | timer_ | 
| Static Protected Attributes | |
| static double | global_angular_threshold = 0.0 | 
| static boost::mutex | global_custom_condigion_function_mutex | 
| static double | global_distance_threshold = 0.0 | 
Definition at line 56 of file region_growing_multiple_plane_segmentation.h.
| typedef RegionGrowingMultiplePlaneSegmentationConfig jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::Config | 
Definition at line 62 of file region_growing_multiple_plane_segmentation.h.
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::NormalSyncPolicy | 
Definition at line 65 of file region_growing_multiple_plane_segmentation.h.
| typedef pcl::PointXYZRGB jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::PointT | 
Definition at line 60 of file region_growing_multiple_plane_segmentation.h.
| jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::RegionGrowingMultiplePlaneSegmentation | ( | ) |  [inline] | 
Definition at line 66 of file region_growing_multiple_plane_segmentation.h.
| void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::configCallback | ( | Config & | config, | 
| uint32_t | level | ||
| ) |  [protected, virtual] | 
Definition at line 92 of file region_growing_multiple_plane_segmentation_nodelet.cpp.
| void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::onInit | ( | void | ) |  [protected, virtual] | 
Definition at line 47 of file region_growing_multiple_plane_segmentation_nodelet.cpp.
| void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::ransacEstimation | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, | 
| const pcl::PointIndices::Ptr & | indices, | ||
| pcl::PointIndices & | inliers, | ||
| pcl::ModelCoefficients & | coefficient | ||
| ) |  [protected, virtual] | 
Definition at line 110 of file region_growing_multiple_plane_segmentation_nodelet.cpp.
| static bool jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::regionGrowingFunction | ( | const pcl::PointXYZRGBNormal & | a, | 
| const pcl::PointXYZRGBNormal & | b, | ||
| float | distance | ||
| ) |  [inline, static, protected] | 
Definition at line 99 of file region_growing_multiple_plane_segmentation.h.
| void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::segment | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg, | 
| const sensor_msgs::PointCloud2::ConstPtr & | normal_msg | ||
| ) |  [protected, virtual] | 
Definition at line 127 of file region_growing_multiple_plane_segmentation_nodelet.cpp.
| static void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::setCondifionFunctionParameter | ( | const double | angular_threshold, | 
| const double | distance_threshold | ||
| ) |  [inline, static, protected] | 
Definition at line 86 of file region_growing_multiple_plane_segmentation.h.
| void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::subscribe | ( | ) |  [protected, virtual] | 
Definition at line 73 of file region_growing_multiple_plane_segmentation_nodelet.cpp.
| void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::unsubscribe | ( | ) |  [protected, virtual] | 
Definition at line 86 of file region_growing_multiple_plane_segmentation_nodelet.cpp.
| double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::angular_threshold_  [protected] | 
Definition at line 149 of file region_growing_multiple_plane_segmentation.h.
| double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::cluster_tolerance_  [protected] | 
Definition at line 156 of file region_growing_multiple_plane_segmentation.h.
| double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::distance_threshold_  [protected] | 
Definition at line 150 of file region_growing_multiple_plane_segmentation.h.
Definition at line 159 of file region_growing_multiple_plane_segmentation.h.
| double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::global_angular_threshold = 0.0  [static, protected] | 
Definition at line 163 of file region_growing_multiple_plane_segmentation.h.
| boost::mutex jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::global_custom_condigion_function_mutex  [static, protected] | 
Definition at line 165 of file region_growing_multiple_plane_segmentation.h.
| double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::global_distance_threshold = 0.0  [static, protected] | 
Definition at line 164 of file region_growing_multiple_plane_segmentation.h.
| double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::max_area_  [protected] | 
Definition at line 155 of file region_growing_multiple_plane_segmentation.h.
| double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::max_curvature_  [protected] | 
Definition at line 151 of file region_growing_multiple_plane_segmentation.h.
| int jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::max_size_  [protected] | 
Definition at line 153 of file region_growing_multiple_plane_segmentation.h.
| double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::min_area_  [protected] | 
Definition at line 154 of file region_growing_multiple_plane_segmentation.h.
| int jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::min_size_  [protected] | 
Definition at line 152 of file region_growing_multiple_plane_segmentation.h.
Definition at line 144 of file region_growing_multiple_plane_segmentation.h.
Definition at line 143 of file region_growing_multiple_plane_segmentation.h.
| ros::Publisher jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::pub_clustering_result_  [protected] | 
Definition at line 141 of file region_growing_multiple_plane_segmentation.h.
Definition at line 140 of file region_growing_multiple_plane_segmentation.h.
Definition at line 139 of file region_growing_multiple_plane_segmentation.h.
Definition at line 142 of file region_growing_multiple_plane_segmentation.h.
Definition at line 138 of file region_growing_multiple_plane_segmentation.h.
Definition at line 158 of file region_growing_multiple_plane_segmentation.h.
| double jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::ransac_refine_outlier_distance_threshold_  [protected] | 
Definition at line 157 of file region_growing_multiple_plane_segmentation.h.
| boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::srv_  [protected] | 
Definition at line 137 of file region_growing_multiple_plane_segmentation.h.
| message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::sub_input_  [protected] | 
Definition at line 133 of file region_growing_multiple_plane_segmentation.h.
| message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::sub_normal_  [protected] | 
Definition at line 134 of file region_growing_multiple_plane_segmentation.h.
| boost::shared_ptr< message_filters::Synchronizer<NormalSyncPolicy> > jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::sync_  [protected] | 
Definition at line 136 of file region_growing_multiple_plane_segmentation.h.
| jsk_recognition_utils::WallDurationTimer jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::timer_  [protected] | 
Definition at line 145 of file region_growing_multiple_plane_segmentation.h.