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_utils/add_point_indices.h"
00038 
00039 
00040 namespace jsk_pcl_ros_utils
00041 {
00042   void AddPointIndices::onInit()
00043   {
00044     DiagnosticNodelet::onInit();
00045     pnh_->param("approximate_sync", approximate_sync_, false);
00046     pub_ = advertise<PCLIndicesMsg>(*pnh_, "output", 1);
00047     onInitPostProcess();
00048   }
00049 
00050   void AddPointIndices::subscribe()
00051   {
00052     sub_src1_.subscribe(*pnh_, "input/src1", 1);
00053     sub_src2_.subscribe(*pnh_, "input/src2", 1);
00054     if (approximate_sync_) {
00055       async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(100);
00056       async_->connectInput(sub_src1_, sub_src2_);
00057       async_->registerCallback(
00058         boost::bind(&AddPointIndices::add,
00059                     this, _1, _2));
00060     }
00061     else {
00062       sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00063       sync_->connectInput(sub_src1_, sub_src2_);
00064       sync_->registerCallback(
00065         boost::bind(&AddPointIndices::add,
00066                     this, _1, _2));
00067     }
00068   }
00069 
00070   void AddPointIndices::unsubscribe()
00071   {
00072     sub_src1_.unsubscribe();
00073     sub_src2_.unsubscribe();
00074   }
00075 
00076   void AddPointIndices::add(
00077     const PCLIndicesMsg::ConstPtr& src1,
00078     const PCLIndicesMsg::ConstPtr& src2)
00079   {
00080     vital_checker_->poke();
00081     pcl::PointIndices a, b;
00082     pcl_conversions::toPCL(*src1, a);
00083     pcl_conversions::toPCL(*src2, b);
00084     pcl::PointIndices::Ptr c = jsk_recognition_utils::addIndices(a, b);
00085     c->header = a.header;
00086     PCLIndicesMsg ros_indices;
00087     pcl_conversions::fromPCL(*c, ros_indices);
00088     ros_indices.header = src1->header;
00089     pub_.publish(ros_indices);
00090   }
00091 }
00092 
00093 #include <pluginlib/class_list_macros.h>
00094 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::AddPointIndices, nodelet::Nodelet);
00095