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;
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
message_filters::Subscriber< PCLIndicesMsg > sub_src2_
virtual void unsubscribe()
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::SubtractPointIndices, nodelet::Nodelet)
void toPCL(const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
virtual void subtract(const PCLIndicesMsg::ConstPtr &src1, const PCLIndicesMsg::ConstPtr &src2)
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)
pcl::PointIndices PCLIndicesMsg
message_filters::Subscriber< PCLIndicesMsg > sub_src1_
std::vector< int > subIndices(const std::vector< int > &a, const std::vector< int > &b)
std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_