Public Types | Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Static Protected Attributes
jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation Class Reference

#include <region_growing_multiple_plane_segmentation.h>

Inheritance diagram for jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation:
Inheritance graph
[legend]

List of all members.

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

Detailed Description

Definition at line 56 of file region_growing_multiple_plane_segmentation.h.


Member Typedef Documentation

typedef RegionGrowingMultiplePlaneSegmentationConfig jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::Config

Definition at line 62 of file region_growing_multiple_plane_segmentation.h.

Definition at line 65 of file region_growing_multiple_plane_segmentation.h.

Definition at line 60 of file region_growing_multiple_plane_segmentation.h.


Constructor & Destructor Documentation

Definition at line 66 of file region_growing_multiple_plane_segmentation.h.


Member Function Documentation

void jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]
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]
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]
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.


Member Data Documentation

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::RegionGrowingMultiplePlaneSegmentation::srv_ [protected]

The documentation for this class was generated from the following files:


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:51