#include <supervoxel_segmentation.h>
Definition at line 79 of file supervoxel_segmentation.h.
◆ Config
◆ PointT
◆ Ptr
◆ SupervoxelSegmentation()
jsk_pcl_ros::SupervoxelSegmentation::SupervoxelSegmentation |
( |
| ) |
|
|
inline |
◆ configCallback()
void jsk_pcl_ros::SupervoxelSegmentation::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ onInit()
void jsk_pcl_ros::SupervoxelSegmentation::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ segment()
void jsk_pcl_ros::SupervoxelSegmentation::segment |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
cloud_msg | ) |
|
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros::SupervoxelSegmentation::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::SupervoxelSegmentation::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ color_importance_
double jsk_pcl_ros::SupervoxelSegmentation::color_importance_ |
|
protected |
◆ mutex_
◆ normal_importance_
double jsk_pcl_ros::SupervoxelSegmentation::normal_importance_ |
|
protected |
◆ pub_cloud_
◆ pub_indices_
◆ seed_resolution_
double jsk_pcl_ros::SupervoxelSegmentation::seed_resolution_ |
|
protected |
◆ spatial_importance_
double jsk_pcl_ros::SupervoxelSegmentation::spatial_importance_ |
|
protected |
◆ srv_
◆ sub_
◆ use_transform_
bool jsk_pcl_ros::SupervoxelSegmentation::use_transform_ |
|
protected |
◆ voxel_resolution_
double jsk_pcl_ros::SupervoxelSegmentation::voxel_resolution_ |
|
protected |
The documentation for this class was generated from the following files: