37 #ifndef _CONVEX_CONNECTED_VOXELS_H_
38 #define _CONVEX_CONNECTED_VOXELS_H_
41 #include <jsk_recognition_msgs/ClusterPointIndices.h>
43 #include <jsk_topic_tools/diagnostic_nodelet.h>
53 #include <sensor_msgs/PointCloud2.h>
57 #include <opencv2/imgproc/imgproc.hpp>
58 #include <opencv2/highgui/highgui.hpp>
61 #include <pcl/point_cloud.h>
62 #include <pcl/point_types.h>
63 #include <pcl/kdtree/kdtree_flann.h>
64 #include <pcl/kdtree/kdtree.h>
65 #include <pcl/filters/passthrough.h>
66 #include <pcl/features/normal_3d_omp.h>
67 #include <pcl/sample_consensus/method_types.h>
68 #include <pcl/sample_consensus/model_types.h>
69 #include <pcl/segmentation/sac_segmentation.h>
70 #include <pcl/segmentation/extract_clusters.h>
71 #include <pcl/filters/extract_indices.h>
72 #include <pcl/common/centroid.h>
73 #include <pcl/common/impl/common.hpp>
74 #include <pcl/registration/distances.h>
82 class ConvexConnectedVoxels:
public jsk_topic_tools::DiagnosticNodelet
86 typedef pcl::PointXYZRGB
PointT;
90 const sensor_msgs::PointCloud2::ConstPtr &);
92 const jsk_recognition_msgs::ClusterPointIndices &);
94 const pcl::PointCloud<PointT>::Ptr,
95 const std::vector<pcl::PointIndices> &,
96 std::vector<pcl::PointCloud<PointT>::Ptr> &,
97 std::vector<pcl::PointCloud<pcl::Normal>::Ptr> &,
98 pcl::PointCloud<pcl::PointXYZ>::Ptr);
100 const pcl::PointCloud<PointT>::Ptr,
101 pcl::PointCloud<pcl::Normal>::Ptr,
102 const int = 8,
const double = 0.02,
105 pcl::PointCloud<pcl::PointXYZ>::Ptr,
106 std::vector<std::vector<int> > &,
111 const std::vector<pcl::PointCloud<PointT>::Ptr> &,
112 pcl::PointCloud<PointT>::Ptr,
113 const std::vector<int> &,
114 std::map<int, pcl::PointIndices> &);
127 std::vector<pcl::PointIndices>
indices_;
131 #endif // _CONVEX_CONNECTED_VOXELS_H_