lightweight_throttle_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 
37 namespace jsk_topic_tools
38 {
40  {
41  pnh_ = this->getPrivateNodeHandle();
43  advertised_ = false;
44  subscribing_ = false;
45 
46  srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(pnh_);
47  dynamic_reconfigure::Server<Config>::CallbackType f =
48  boost::bind(&LightweightThrottle::configCallback, this, _1, _2);
49  srv_->setCallback(f);
50 
51  // Subscribe input topic at first in order to decide
52  // message type of publisher.
53  // nodelet will unsubscribe input topic after it receives the first topic.
54  sub_.reset(new ros::Subscriber(
57  this,
58  th_)));
59  }
60 
61  void LightweightThrottle::configCallback(Config& config, uint32_t level)
62  {
63  boost::mutex::scoped_lock lock(mutex_);
64  update_rate_ = config.update_rate;
65  }
66 
69  {
70  if (pub_.getNumSubscribers() > 0) {
71  if (!subscribing_) {
72  sub_.reset(new ros::Subscriber(
74  "input", 1,
76  this,
77  th_)));
78  subscribing_ = true;
79  }
80  }
81  else { // No subscribers, nodelet can unsubscribe input topic
82  if (subscribing_) {
83  sub_->shutdown();
84  subscribing_ = false;
85  }
86  }
87  }
88 
91  {
92  boost::mutex::scoped_lock lock(mutex_);
93  // advertise if not
94  if (!advertised_) {
95  // This section should be called once
96  sub_->shutdown(); // Shutdown before advertising topic
98  = boost::bind(&LightweightThrottle::connectionCallback, this, _1);
99  ros::AdvertiseOptions opts("output", 1,
100  msg->getMD5Sum(),
101  msg->getDataType(),
102  msg->getMessageDefinition(),
103  connect_cb,
104  connect_cb);
105  advertised_ = true;
106  pub_ = pnh_.advertise(opts);
107  }
108 
109  ros::Time now = ros::Time::now();
110 
111  if (latest_stamp_ > now) {
112  ROS_WARN("Detected jump back in time. latest_stamp_ is overwritten.");
113  latest_stamp_ = now;
114  }
115 
116  if (update_rate_ > 0.0 && (now - latest_stamp_).toSec() > 1.0 / update_rate_) {
117  pub_.publish(msg);
118  latest_stamp_ = now;
119  }
120  }
121 }
122 
virtual void configCallback(Config &config, uint32_t level)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void publish(const boost::shared_ptr< M > &message) const
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual void inCallback(const boost::shared_ptr< topic_tools::ShapeShifter const > &msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
PLUGINLIB_EXPORT_CLASS(jsk_topic_tools::Snapshot, nodelet::Nodelet)
jsk_topic_tools::LightweightThrottle LightweightThrottle
#define ROS_WARN(...)
ros::NodeHandle & getPrivateNodeHandle() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
static Time now()
virtual void connectionCallback(const ros::SingleSubscriberPublisher &pub)


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Tue Feb 6 2018 03:45:19