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 
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include "jsk_pcl_ros/extract_indices.h"
00038 #include "jsk_recognition_utils/pcl_conversion_util.h"
00039 
00040 #if PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 8
00041 #include <pcl/filters/extract_indices.h>
00042 #else
00043 #include "jsk_pcl_ros/pcl/extract_indices_patch.h"
00044 #endif
00045 #include <pcl_conversions/pcl_conversions.h>
00046 #include <sensor_msgs/PointCloud2.h>
00047 
00048 namespace jsk_pcl_ros
00049 {
00050   void ExtractIndices::onInit()
00051   {
00052     DiagnosticNodelet::onInit();
00053     pnh_->param("keep_organized", keep_organized_, false);
00054     pnh_->param("negative", negative_, false);
00055     pnh_->param("max_queue_size", max_queue_size_, 10);
00056     pnh_->param("approximate_sync", approximate_sync_, false);
00057     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00058     onInitPostProcess();
00059   }
00060 
00061   void ExtractIndices::subscribe()
00062   {
00063     sub_cloud_.subscribe(*pnh_, "input", max_queue_size_);
00064     sub_indices_.subscribe(*pnh_, "indices", max_queue_size_);
00065     if (approximate_sync_) {
00066       async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(100);
00067       async_->connectInput(sub_indices_, sub_cloud_);
00068       async_->registerCallback(
00069         boost::bind(&ExtractIndices::convert, this, _1, _2));
00070     }
00071     else {
00072       sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00073       sync_->connectInput(sub_indices_, sub_cloud_);
00074       sync_->registerCallback(
00075         boost::bind(&ExtractIndices::convert, this, _1, _2));
00076     }
00077   }
00078 
00079   void ExtractIndices::unsubscribe()
00080   {
00081     sub_cloud_.unsubscribe();
00082     sub_indices_.unsubscribe();
00083   }
00084 
00085   void ExtractIndices::convert(
00086     const PCLIndicesMsg::ConstPtr& indices_msg,
00087     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
00088   {
00089     vital_checker_->poke();
00090 
00091     pcl::PCLPointCloud2::Ptr input(new pcl::PCLPointCloud2);
00092     pcl_conversions::toPCL(*cloud_msg, *input);
00093     pcl::PointIndices::Ptr indices (new pcl::PointIndices ());
00094     pcl_conversions::toPCL(*indices_msg, *indices);
00095 
00096     
00097     pcl::ExtractIndices<pcl::PCLPointCloud2> extract;
00098     extract.setInputCloud(input);
00099     extract.setIndices(indices);
00100     extract.setKeepOrganized(keep_organized_);
00101     extract.setNegative(negative_);
00102     pcl::PCLPointCloud2 output;
00103     extract.filter(output);
00104 
00105     sensor_msgs::PointCloud2 out_cloud_msg;
00106 #if PCL_MAJOR_VERSION <= 1 && PCL_MINOR_VERSION < 8
00107     if (indices_msg->indices.empty() || cloud_msg->data.empty()) {
00108       out_cloud_msg.height = cloud_msg->height;
00109       out_cloud_msg.width = cloud_msg->width;
00110     }
00111 #endif
00112     pcl_conversions::moveFromPCL(output, out_cloud_msg);
00113 
00114     out_cloud_msg.header = cloud_msg->header;
00115     pub_.publish(out_cloud_msg);
00116   }
00117 }
00118 
00119 #include <pluginlib/class_list_macros.h>
00120 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::ExtractIndices, nodelet::Nodelet);