Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 #include "jsk_pcl_ros/selected_cluster_publisher.h"
00036 #include <pluginlib/class_list_macros.h>
00037 #include <pcl/filters/extract_indices.h>
00038 
00039 #include "jsk_recognition_utils/pcl_conversion_util.h"
00040 
00041 namespace jsk_pcl_ros
00042 {
00043   void SelectedClusterPublisher::onInit()
00044   {
00045     ConnectionBasedNodelet::onInit();
00046     pnh_->param("keep_organized", keep_organized_, false);
00047     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00048     onInitPostProcess();
00049   }
00050 
00051   void SelectedClusterPublisher::subscribe()
00052   {
00053     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(300); 
00054     sub_input_.subscribe(*pnh_, "input", 1);
00055     sub_indices_.subscribe(*pnh_, "indices", 1);
00056     sub_index_.subscribe(*pnh_, "selected_index", 1);
00057     sync_->connectInput(sub_input_, sub_indices_, sub_index_);
00058     sync_->registerCallback(boost::bind(&SelectedClusterPublisher::extract, this, _1, _2, _3));
00059   }
00060 
00061   void SelectedClusterPublisher::unsubscribe()
00062   {
00063     sub_input_.unsubscribe();
00064     sub_indices_.unsubscribe();
00065     sub_index_.unsubscribe();
00066   }
00067 
00068   void SelectedClusterPublisher::extract(const sensor_msgs::PointCloud2::ConstPtr& input,
00069                                          const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices,
00070                                          const jsk_recognition_msgs::Int32Stamped::ConstPtr& index)
00071   {
00072     if (indices->cluster_indices.size() <= index->data) {
00073       NODELET_ERROR("the selected index %d is out of clusters array %lu",
00074                     index->data,
00075                     indices->cluster_indices.size());
00076       return;
00077     }
00078     pcl::PointCloud<pcl::PointXYZRGB>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZRGB>());
00079     pcl::fromROSMsg(*input, *input_cloud);
00080     pcl::ExtractIndices<pcl::PointXYZRGB> extract;
00081     pcl::PointIndices::Ptr pcl_indices (new pcl::PointIndices);
00082     pcl_indices->indices = indices->cluster_indices[index->data].indices;
00083     extract.setInputCloud(input_cloud);
00084     extract.setIndices(pcl_indices);
00085     pcl::PointCloud<pcl::PointXYZRGB>::Ptr extracted_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
00086     if(keep_organized_){
00087       extract.setKeepOrganized(true);
00088     }
00089     extract.filter(*extracted_cloud);
00090     sensor_msgs::PointCloud2 ros_msg;
00091     pcl::toROSMsg(*extracted_cloud, ros_msg);
00092     ros_msg.header = input->header;
00093     pub_.publish(ros_msg);
00094   }
00095 }
00096 
00097 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::SelectedClusterPublisher,
00098                         nodelet::Nodelet);