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