Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::SupervoxelSegmentation Class Reference

#include <supervoxel_segmentation.h>

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

Public Types

typedef SupervoxelSegmentationConfig Config
 
typedef pcl::PointXYZRGB PointT
 
typedef boost::shared_ptr< SupervoxelSegmentationPtr
 

Public Member Functions

 SupervoxelSegmentation ()
 

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
 
virtual void onInit ()
 
virtual void segment (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 

Protected Attributes

double color_importance_
 
boost::mutex mutex_
 
double normal_importance_
 
ros::Publisher pub_cloud_
 
ros::Publisher pub_indices_
 
double seed_resolution_
 
double spatial_importance_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
ros::Subscriber sub_
 
bool use_transform_
 
double voxel_resolution_
 

Detailed Description

Definition at line 79 of file supervoxel_segmentation.h.

Member Typedef Documentation

◆ Config

typedef SupervoxelSegmentationConfig jsk_pcl_ros::SupervoxelSegmentation::Config

Definition at line 116 of file supervoxel_segmentation.h.

◆ PointT

Definition at line 114 of file supervoxel_segmentation.h.

◆ Ptr

Definition at line 115 of file supervoxel_segmentation.h.

Constructor & Destructor Documentation

◆ SupervoxelSegmentation()

jsk_pcl_ros::SupervoxelSegmentation::SupervoxelSegmentation ( )
inline

Definition at line 117 of file supervoxel_segmentation.h.

Member Function Documentation

◆ configCallback()

void jsk_pcl_ros::SupervoxelSegmentation::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

Definition at line 116 of file supervoxel_segmentation_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::SupervoxelSegmentation::onInit ( )
protectedvirtual

Definition at line 41 of file supervoxel_segmentation_nodelet.cpp.

◆ segment()

void jsk_pcl_ros::SupervoxelSegmentation::segment ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg)
protectedvirtual

Definition at line 66 of file supervoxel_segmentation_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::SupervoxelSegmentation::subscribe ( )
protectedvirtual

Definition at line 56 of file supervoxel_segmentation_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::SupervoxelSegmentation::unsubscribe ( )
protectedvirtual

Definition at line 61 of file supervoxel_segmentation_nodelet.cpp.

Member Data Documentation

◆ color_importance_

double jsk_pcl_ros::SupervoxelSegmentation::color_importance_
protected

Definition at line 140 of file supervoxel_segmentation.h.

◆ mutex_

boost::mutex jsk_pcl_ros::SupervoxelSegmentation::mutex_
protected

Definition at line 131 of file supervoxel_segmentation.h.

◆ normal_importance_

double jsk_pcl_ros::SupervoxelSegmentation::normal_importance_
protected

Definition at line 142 of file supervoxel_segmentation.h.

◆ pub_cloud_

ros::Publisher jsk_pcl_ros::SupervoxelSegmentation::pub_cloud_
protected

Definition at line 135 of file supervoxel_segmentation.h.

◆ pub_indices_

ros::Publisher jsk_pcl_ros::SupervoxelSegmentation::pub_indices_
protected

Definition at line 134 of file supervoxel_segmentation.h.

◆ seed_resolution_

double jsk_pcl_ros::SupervoxelSegmentation::seed_resolution_
protected

Definition at line 144 of file supervoxel_segmentation.h.

◆ spatial_importance_

double jsk_pcl_ros::SupervoxelSegmentation::spatial_importance_
protected

Definition at line 141 of file supervoxel_segmentation.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::SupervoxelSegmentation::srv_
protected

Definition at line 133 of file supervoxel_segmentation.h.

◆ sub_

ros::Subscriber jsk_pcl_ros::SupervoxelSegmentation::sub_
protected

Definition at line 132 of file supervoxel_segmentation.h.

◆ use_transform_

bool jsk_pcl_ros::SupervoxelSegmentation::use_transform_
protected

Definition at line 145 of file supervoxel_segmentation.h.

◆ voxel_resolution_

double jsk_pcl_ros::SupervoxelSegmentation::voxel_resolution_
protected

Definition at line 143 of file supervoxel_segmentation.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:46