nodelet_lazy.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014-2016, JSK Lab, University of Tokyo.
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 
35 /* Author: Ryohei Ueda, Kentaro Wada <www.kentaro.wada@gmail.com>
36  */
37 
38 #ifndef NODELET_LAZY_H_
39 #define NODELET_LAZY_H_
40 
41 #include <ros/ros.h>
42 #include <nodelet/nodelet.h>
43 #include <boost/thread.hpp>
44 #include <string>
45 #include <vector>
46 
48 {
49 
54 {
58 };
59 
71 {
72 public:
74 
75 protected:
80  virtual void onInit()
81  {
83  bool use_multithread;
84  ros::param::param<bool>("~use_multithread_callback", use_multithread, true);
85  if (use_multithread)
86  {
87  NODELET_DEBUG("Using multithread callback");
88  nh_.reset (new ros::NodeHandle(getMTNodeHandle()));
90  }
91  else
92  {
93  NODELET_DEBUG("Using singlethread callback");
94  nh_.reset(new ros::NodeHandle(getNodeHandle()));
96  }
97  // option to use lazy transport
98  pnh_->param("lazy", lazy_, true);
99  // option for logging about being subscribed
100  pnh_->param("verbose_connection", verbose_connection_, false);
101  if (!verbose_connection_)
102  {
103  nh_->param("verbose_connection", verbose_connection_, false);
104  }
105  // timer to warn when no connection in the specified seconds
106  ever_subscribed_ = false;
107  double duration_to_warn_no_connection;
108  pnh_->param("duration_to_warn_no_connection",
109  duration_to_warn_no_connection, 5.0);
110  if (duration_to_warn_no_connection > 0)
111  {
112  timer_ever_subscribed_ = nh_->createWallTimer(
113  ros::WallDuration(duration_to_warn_no_connection),
115  this,
116  /*oneshot=*/true);
117  }
118  }
119 
125  virtual void onInitPostProcess()
126  {
127  if (!lazy_)
128  {
129  boost::mutex::scoped_lock lock(connection_mutex_);
130  subscribe();
131  ever_subscribed_ = true;
132  }
133  }
134 
139  {
141  {
142  NODELET_INFO("New connection or disconnection is detected");
143  }
144  if (lazy_)
145  {
146  boost::mutex::scoped_lock lock(connection_mutex_);
147  for (size_t i = 0; i < publishers_.size(); i++)
148  {
149  ros::Publisher pub = publishers_[i];
150  if (pub.getNumSubscribers() > 0)
151  {
153  {
155  {
156  NODELET_INFO("Subscribe input topics");
157  }
158  subscribe();
160  }
161  if (!ever_subscribed_)
162  {
163  ever_subscribed_ = true;
164  }
165  return;
166  }
167  }
169  {
171  {
172  NODELET_INFO("Unsubscribe input topics");
173  }
174  unsubscribe();
176  }
177  }
178  }
179 
185  {
186  if (!ever_subscribed_)
187  {
188  NODELET_WARN("This node/nodelet subscribes topics only when subscribed.");
189  }
190  }
191 
192 
198  virtual void subscribe() = 0;
199 
205  virtual void unsubscribe() = 0;
206 
218  template<class T> ros::Publisher
220  std::string topic, int queue_size, bool latch=false)
221  {
222  boost::mutex::scoped_lock lock(connection_mutex_);
224  = boost::bind(&NodeletLazy::connectionCallback, this, _1);
225  ros::SubscriberStatusCallback disconnect_cb
226  = boost::bind(&NodeletLazy::connectionCallback, this, _1);
227  ros::Publisher pub = nh.advertise<T>(topic, queue_size,
228  connect_cb,
229  disconnect_cb,
231  latch);
232  publishers_.push_back(pub);
233  return pub;
234  }
235 
240  boost::mutex connection_mutex_;
241 
246 
251 
255  std::vector<ros::Publisher> publishers_;
256 
261 
267 
272  bool lazy_;
273 
278 
283 
284 private:
285 };
286 
287 } // namespace nodelet_topic_tools
288 
289 #endif // NODELET_LAZY_H_
boost::mutex connection_mutex_
mutex to call subscribe() and unsubscribe() in critical section.
Definition: nodelet_lazy.h:240
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
Definition: nodelet_lazy.h:125
boost::shared_ptr< void const > VoidConstPtr
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
#define NODELET_WARN(...)
bool ever_subscribed_
A flag to check if the node has been ever subscribed or not.
Definition: nodelet_lazy.h:266
virtual void connectionCallback(const ros::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come
Definition: nodelet_lazy.h:138
ros::WallTimer timer_ever_subscribed_
WallTimer instance for warning about no connection.
Definition: nodelet_lazy.h:260
ros::NodeHandle & getMTNodeHandle() const
virtual void subscribe()=0
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
std::vector< ros::Publisher > publishers_
List of watching publishers.
Definition: nodelet_lazy.h:255
ros::NodeHandle & getPrivateNodeHandle() const
bool verbose_connection_
true if ~verbose_connection or verbose_connection parameter is true.
Definition: nodelet_lazy.h:282
bool lazy_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~lazy...
Definition: nodelet_lazy.h:272
ros::NodeHandle & getMTPrivateNodeHandle() const
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet_lazy.h:250
ros::Publisher advertise(ros::NodeHandle &nh, std::string topic, int queue_size, bool latch=false)
Update the list of Publishers created by this method. It automatically reads latch boolean parameter ...
Definition: nodelet_lazy.h:219
ConnectionStatus connection_status_
Status of connection.
Definition: nodelet_lazy.h:277
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Definition: nodelet_lazy.h:70
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent &event)
callback function which is called when walltimer duration run out.
Definition: nodelet_lazy.h:184
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
Definition: nodelet_lazy.h:80
ConnectionStatus
Enum to represent connection status.
Definition: nodelet_lazy.h:53
virtual void unsubscribe()=0
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet_lazy.h:245
#define NODELET_DEBUG(...)


nodelet_topic_tools
Author(s): Radu Bogdan Rusu, Tully Foote
autogenerated on Mon Feb 18 2019 03:26:48