36 #define BOOST_PARAMETER_MAX_ARITY 7
38 #include <pcl/segmentation/supervoxel_clustering.h>
43 DiagnosticNodelet::onInit();
44 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
45 dynamic_reconfigure::Server<Config>::CallbackType
f =
48 srv_->setCallback (
f);
49 pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
50 *pnh_,
"output/indices", 1);
51 pub_cloud_ = advertise<sensor_msgs::PointCloud2>(
52 *pnh_,
"output/cloud", 1);
67 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
70 vital_checker_->poke();
71 if (cloud_msg->data.size() > 0) {
72 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
76 #
if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
81 super.setInputCloud(
cloud);
85 std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr > supervoxel_clusters;
86 super.extract(supervoxel_clusters);
87 pcl::PointCloud<PointT>::Ptr output (
new pcl::PointCloud<PointT>);
88 std::vector<pcl::PointIndices> all_indices;
89 for (std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr >::iterator
90 it = supervoxel_clusters.begin();
91 it != supervoxel_clusters.end();
93 pcl::Supervoxel<PointT>::Ptr super_voxel = it->second;
94 pcl::PointCloud<PointT>::Ptr super_voxel_cloud = super_voxel->voxels_;
95 pcl::PointIndices indices;
97 for (
size_t i = 0;
i < super_voxel_cloud->size();
i++) {
98 indices.indices.push_back(
i + output->points.size());
100 all_indices.push_back(indices);
101 *output = *output + *super_voxel_cloud;
103 sensor_msgs::PointCloud2 ros_cloud;
105 ros_cloud.header = cloud_msg->header;
106 jsk_recognition_msgs::ClusterPointIndices ros_indices;
110 ros_indices.header = cloud_msg->header;