#include <convex_connected_voxels.h>
| 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_ | 
Definition at line 82 of file convex_connected_voxels.h.
| typedef pcl::PointXYZRGB jsk_pcl_ros::ConvexConnectedVoxels::PointT | 
Definition at line 86 of file convex_connected_voxels.h.
Definition at line 85 of file convex_connected_voxels.h.
| void jsk_pcl_ros::ConvexConnectedVoxels::cloud_cb | ( | const sensor_msgs::PointCloud2::ConstPtr & | cloud_msg | ) |  [protected] | 
Definition at line 65 of file convex_connected_voxels_nodelet.cpp.
| 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 163 of file convex_connected_voxels_nodelet.cpp.
| 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 206 of file convex_connected_voxels_nodelet.cpp.
| void jsk_pcl_ros::ConvexConnectedVoxels::indices_cb | ( | const jsk_recognition_msgs::ClusterPointIndices & | indices_msg | ) |  [protected] | 
Definition at line 111 of file convex_connected_voxels_nodelet.cpp.
| 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 182 of file convex_connected_voxels_nodelet.cpp.
| void jsk_pcl_ros::ConvexConnectedVoxels::onInit | ( | void | ) |  [protected, virtual] | 
Definition at line 40 of file convex_connected_voxels_nodelet.cpp.
| 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 126 of file convex_connected_voxels_nodelet.cpp.
| void jsk_pcl_ros::ConvexConnectedVoxels::subscribe | ( | ) |  [protected, virtual] | 
Definition at line 49 of file convex_connected_voxels_nodelet.cpp.
| void jsk_pcl_ros::ConvexConnectedVoxels::unsubscribe | ( | ) |  [protected, virtual] | 
Definition at line 59 of file convex_connected_voxels_nodelet.cpp.
| std::vector<pcl::PointIndices> jsk_pcl_ros::ConvexConnectedVoxels::indices_  [private] | 
Definition at line 127 of file convex_connected_voxels.h.
Definition at line 116 of file convex_connected_voxels.h.
Definition at line 120 of file convex_connected_voxels.h.
Definition at line 119 of file convex_connected_voxels.h.
Definition at line 117 of file convex_connected_voxels.h.
Definition at line 118 of file convex_connected_voxels.h.