36 #define BOOST_PARAMETER_MAX_ARITY 7 44 DiagnosticNodelet::onInit();
46 pub_ = advertise<PCLIndicesMsg>(*
pnh_,
"output", 1);
55 async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(100);
62 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
64 sync_->registerCallback(
77 const PCLIndicesMsg::ConstPtr& src1,
78 const PCLIndicesMsg::ConstPtr& src2)
81 pcl::PointIndices
a,
b;
88 ros_indices.header = src1->header;
message_filters::Subscriber< PCLIndicesMsg > sub_src2_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::AddPointIndices, nodelet::Nodelet)
void publish(const boost::shared_ptr< M > &message) const
virtual void add(const PCLIndicesMsg::ConstPtr &src1, const PCLIndicesMsg::ConstPtr &src2)
void toPCL(const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
std::vector< int > addIndices(const std::vector< int > &a, const std::vector< int > &b)
message_filters::Subscriber< PCLIndicesMsg > sub_src1_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
pcl::PointIndices PCLIndicesMsg
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header)
virtual void unsubscribe()