delay_pointcloud_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
38 
39 namespace jsk_pcl_ros_utils
40 {
42  {
43  ConnectionBasedNodelet::onInit();
44 
45  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
46  dynamic_reconfigure::Server<Config>::CallbackType f =
47  boost::bind (&DelayPointCloud::configCallback, this, _1, _2);
48  srv_->setCallback (f);
49 
50  pnh_->param("delay_time", delay_time_, 0.1);
51  pnh_->param("queue_size", queue_size_, 1000);
52  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", queue_size_);
53  }
54 
55  void DelayPointCloud::configCallback(Config &config, uint32_t level)
56  {
57  boost::mutex::scoped_lock lock(mutex_);
58 
59  delay_time_ = config.delay_time;
61  }
62 
63  void DelayPointCloud::delay(const sensor_msgs::PointCloud2::ConstPtr& msg)
64  {
65  sensor_msgs::PointCloud2 out_cloud_msg = *msg;
66  out_cloud_msg.header.stamp = ros::Time::now();
67  pub_.publish(out_cloud_msg);
68  }
69 
71  {
72  sub_.subscribe(*pnh_, "input", 1);
73  time_sequencer_ = boost::make_shared<message_filters::TimeSequencer<sensor_msgs::PointCloud2> >(ros::Duration(delay_time_), ros::Duration(0.01), queue_size_);
74  time_sequencer_->connectInput(sub_);
75  time_sequencer_->registerCallback(boost::bind(&DelayPointCloud::delay, this, _1));
76  }
78  {
79  sub_.unsubscribe();
80  }
81 }
82 
f
lock
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_
boost::shared_ptr< ros::NodeHandle > pnh_
void configCallback(Config &config, uint32_t level)
boost::shared_ptr< message_filters::TimeSequencer< sensor_msgs::PointCloud2 > > time_sequencer_
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)
static Time now()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15