43 ConnectionBasedNodelet::onInit();
45 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
46 dynamic_reconfigure::Server<Config>::CallbackType
f =
48 srv_->setCallback (f);
65 sensor_msgs::PointCloud2 out_cloud_msg = *msg;
void publish(const boost::shared_ptr< M > &message) const
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::DelayPointCloud, nodelet::Nodelet)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_
void configCallback(Config &config, uint32_t level)
boost::shared_ptr< message_filters::TimeSequencer< sensor_msgs::PointCloud2 > > time_sequencer_
virtual void unsubscribe()
jsk_pcl_ros_utils::DelayPointCloudConfig Config
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)
virtual void delay(const sensor_msgs::PointCloud2::ConstPtr &msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_