Protected Types | Protected Member Functions | Protected Attributes | Private Member Functions
jsk_pcl_ros::RegionGrowingSegmentation Class Reference

#include <region_growing_segmentation.h>

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

List of all members.

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 ()

Detailed Description

Definition at line 53 of file region_growing_segmentation.h.


Member Typedef Documentation

typedef jsk_pcl_ros::RegionGrowingSegmentationConfig jsk_pcl_ros::RegionGrowingSegmentation::Config [protected]

Definition at line 65 of file region_growing_segmentation.h.


Member Function Documentation

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.

Definition at line 58 of file region_growing_segmentation_nodelet.cpp.

Definition at line 63 of file region_growing_segmentation_nodelet.cpp.


Member Data Documentation

Definition at line 64 of file region_growing_segmentation.h.

Definition at line 62 of file region_growing_segmentation.h.

Definition at line 61 of file region_growing_segmentation.h.

Definition at line 67 of file region_growing_segmentation.h.

Definition at line 60 of file region_growing_segmentation.h.

Definition at line 58 of file region_growing_segmentation.h.

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.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:47