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

#include <convex_connected_voxels.h>

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

Public Types

typedef pcl::PointXYZRGB PointT
 

Public Member Functions

 ConvexConnectedVoxels ()
 

Protected Member Functions

void cloud_cb (const sensor_msgs::PointCloud2::ConstPtr &)
 
void estimatePointCloudNormals (const pcl::PointCloud< PointT >::Ptr, pcl::PointCloud< pcl::Normal >::Ptr, const int=8, const double=0.02, bool=true)
 
void getConvexLabelCloudIndices (const std::vector< pcl::PointCloud< PointT >::Ptr > &, pcl::PointCloud< PointT >::Ptr, const std::vector< int > &, std::map< int, pcl::PointIndices > &)
 
void indices_cb (const jsk_recognition_msgs::ClusterPointIndices &)
 
void nearestNeigborSearch (pcl::PointCloud< pcl::PointXYZ >::Ptr, std::vector< std::vector< int > > &, const int=8, const double=0.02, bool=true)
 
virtual void onInit ()
 
void segmentCloud (const pcl::PointCloud< PointT >::Ptr, const std::vector< pcl::PointIndices > &, std::vector< pcl::PointCloud< PointT >::Ptr > &, std::vector< pcl::PointCloud< pcl::Normal >::Ptr > &, pcl::PointCloud< pcl::PointXYZ >::Ptr)
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 

Protected Attributes

boost::mutex mutex_
 
ros::NodeHandle nh_
 
ros::Publisher pub_indices_
 
ros::Subscriber sub_cloud_
 
ros::Subscriber sub_indices_
 

Private Attributes

std::vector< pcl::PointIndices > indices_
 

Detailed Description

Definition at line 114 of file convex_connected_voxels.h.

Member Typedef Documentation

◆ PointT

Definition at line 150 of file convex_connected_voxels.h.

Constructor & Destructor Documentation

◆ ConvexConnectedVoxels()

jsk_pcl_ros::ConvexConnectedVoxels::ConvexConnectedVoxels ( )
inline

Definition at line 149 of file convex_connected_voxels.h.

Member Function Documentation

◆ cloud_cb()

void jsk_pcl_ros::ConvexConnectedVoxels::cloud_cb ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg)
protected

Definition at line 97 of file convex_connected_voxels_nodelet.cpp.

◆ estimatePointCloudNormals()

void jsk_pcl_ros::ConvexConnectedVoxels::estimatePointCloudNormals ( const pcl::PointCloud< PointT >::Ptr  cloud,
pcl::PointCloud< pcl::Normal >::Ptr  s_normal,
const int  k = 8,
const double  radius = 0.02,
bool  ksearch = true 
)
protected

Definition at line 195 of file convex_connected_voxels_nodelet.cpp.

◆ getConvexLabelCloudIndices()

void jsk_pcl_ros::ConvexConnectedVoxels::getConvexLabelCloudIndices ( const std::vector< pcl::PointCloud< PointT >::Ptr > &  cloud_clusters,
pcl::PointCloud< PointT >::Ptr  cloud,
const std::vector< int > &  labelMD,
std::map< int, pcl::PointIndices > &  all_indices 
)
protected

Definition at line 238 of file convex_connected_voxels_nodelet.cpp.

◆ indices_cb()

void jsk_pcl_ros::ConvexConnectedVoxels::indices_cb ( const jsk_recognition_msgs::ClusterPointIndices &  indices_msg)
protected

Definition at line 143 of file convex_connected_voxels_nodelet.cpp.

◆ nearestNeigborSearch()

void jsk_pcl_ros::ConvexConnectedVoxels::nearestNeigborSearch ( pcl::PointCloud< pcl::PointXYZ >::Ptr  cloud,
std::vector< std::vector< int > > &  pointIndices,
const int  k = 8,
const double  radius = 0.02,
bool  isneigbour = true 
)
protected

Definition at line 214 of file convex_connected_voxels_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::ConvexConnectedVoxels::onInit ( )
protectedvirtual

Definition at line 72 of file convex_connected_voxels_nodelet.cpp.

◆ segmentCloud()

void jsk_pcl_ros::ConvexConnectedVoxels::segmentCloud ( const pcl::PointCloud< PointT >::Ptr  cloud,
const std::vector< pcl::PointIndices > &  indices,
std::vector< pcl::PointCloud< PointT >::Ptr > &  cloud_clusters,
std::vector< pcl::PointCloud< pcl::Normal >::Ptr > &  normal_clusters,
pcl::PointCloud< pcl::PointXYZ >::Ptr  centroids 
)
protected

Definition at line 158 of file convex_connected_voxels_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::ConvexConnectedVoxels::subscribe ( )
protectedvirtual

Definition at line 81 of file convex_connected_voxels_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::ConvexConnectedVoxels::unsubscribe ( )
protectedvirtual

Definition at line 91 of file convex_connected_voxels_nodelet.cpp.

Member Data Documentation

◆ indices_

std::vector<pcl::PointIndices> jsk_pcl_ros::ConvexConnectedVoxels::indices_
private

Definition at line 191 of file convex_connected_voxels.h.

◆ mutex_

boost::mutex jsk_pcl_ros::ConvexConnectedVoxels::mutex_
protected

Definition at line 180 of file convex_connected_voxels.h.

◆ nh_

ros::NodeHandle jsk_pcl_ros::ConvexConnectedVoxels::nh_
protected

Definition at line 184 of file convex_connected_voxels.h.

◆ pub_indices_

ros::Publisher jsk_pcl_ros::ConvexConnectedVoxels::pub_indices_
protected

Definition at line 183 of file convex_connected_voxels.h.

◆ sub_cloud_

ros::Subscriber jsk_pcl_ros::ConvexConnectedVoxels::sub_cloud_
protected

Definition at line 181 of file convex_connected_voxels.h.

◆ sub_indices_

ros::Subscriber jsk_pcl_ros::ConvexConnectedVoxels::sub_indices_
protected

Definition at line 182 of file convex_connected_voxels.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:45