37 #include <pcl/filters/extract_indices.h>
45 ConnectionBasedNodelet::onInit();
47 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
"output", 1);
64 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(300);
80 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices,
81 const jsk_recognition_msgs::Int32Stamped::ConstPtr& index)
83 if (indices->cluster_indices.size() <=
index->data) {
84 NODELET_ERROR(
"the selected index %d is out of clusters array %lu",
86 indices->cluster_indices.size());
89 pcl::PointCloud<pcl::PointXYZRGB>::Ptr input_cloud (
new pcl::PointCloud<pcl::PointXYZRGB>());
91 pcl::ExtractIndices<pcl::PointXYZRGB>
extract;
92 pcl::PointIndices::Ptr pcl_indices (
new pcl::PointIndices);
93 pcl_indices->indices = indices->cluster_indices[
index->data].indices;
95 extract.setIndices(pcl_indices);
96 pcl::PointCloud<pcl::PointXYZRGB>::Ptr extracted_cloud(
new pcl::PointCloud<pcl::PointXYZRGB>());
100 extract.filter(*extracted_cloud);
101 sensor_msgs::PointCloud2 ros_msg;
103 ros_msg.header =
input->header;