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 #include "jsk_pcl_ros_utils/delay_pointcloud.h"
00037 #include <pluginlib/class_list_macros.h>
00038
00039 namespace jsk_pcl_ros_utils
00040 {
00041 void DelayPointCloud::onInit()
00042 {
00043 ConnectionBasedNodelet::onInit();
00044
00045 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00046 dynamic_reconfigure::Server<Config>::CallbackType f =
00047 boost::bind (&DelayPointCloud::configCallback, this, _1, _2);
00048 srv_->setCallback (f);
00049
00050 pnh_->param("delay_time", delay_time_, 0.1);
00051 pnh_->param("queue_size", queue_size_, 1000);
00052 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", queue_size_);
00053 }
00054
00055 void DelayPointCloud::configCallback(Config &config, uint32_t level)
00056 {
00057 boost::mutex::scoped_lock lock(mutex_);
00058
00059 delay_time_ = config.delay_time;
00060 DelayPointCloud::subscribe();
00061 }
00062
00063 void DelayPointCloud::delay(const sensor_msgs::PointCloud2::ConstPtr& msg)
00064 {
00065 sensor_msgs::PointCloud2 out_cloud_msg = *msg;
00066 out_cloud_msg.header.stamp = ros::Time::now();
00067 pub_.publish(out_cloud_msg);
00068 }
00069
00070 void DelayPointCloud::subscribe()
00071 {
00072 sub_.subscribe(*pnh_, "input", 1);
00073 time_sequencer_ = boost::make_shared<message_filters::TimeSequencer<sensor_msgs::PointCloud2> >(ros::Duration(delay_time_), ros::Duration(0.01), queue_size_);
00074 time_sequencer_->connectInput(sub_);
00075 time_sequencer_->registerCallback(boost::bind(&DelayPointCloud::delay, this, _1));
00076 }
00077 void DelayPointCloud::unsubscribe()
00078 {
00079 sub_.unsubscribe();
00080 }
00081 }
00082
00083 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::DelayPointCloud, nodelet::Nodelet);