connection_based_nodelet.h
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 
36 
37 #ifndef CONNECTION_BASED_NODELET_H_
38 #define CONNECTION_BASED_NODELET_H_
39 
40 #include <ros/ros.h>
41 #include <nodelet/nodelet.h>
42 #include <boost/thread.hpp>
45 
46 namespace jsk_topic_tools
47 {
52  {
56  };
57 
69  {
70  public:
72  protected:
73 
78  virtual void onInit();
79 
80 
86  virtual void onInitPostProcess();
87 
92 
97  virtual void imageConnectionCallback(
99 
104  virtual void cameraConnectionCallback(
106 
111  virtual void cameraInfoConnectionCallback(
112  const ros::SingleSubscriberPublisher& pub);
113 
120  virtual void cameraConnectionBaseCallback();
121 
126  virtual void warnOnInitPostProcessCalledCallback(const ros::WallTimerEvent& event);
127 
132  virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent& event);
133 
139  virtual void subscribe() = 0;
140 
146  virtual void unsubscribe() = 0;
147 
151  virtual bool isSubscribed();
152 
165  template<class T> ros::Publisher
167  std::string topic, int queue_size)
168  {
169  boost::mutex::scoped_lock lock(connection_mutex_);
171  = boost::bind(&ConnectionBasedNodelet::connectionCallback, this, _1);
172  ros::SubscriberStatusCallback disconnect_cb
173  = boost::bind(&ConnectionBasedNodelet::connectionCallback, this, _1);
174  bool latch;
175  nh.param("latch", latch, false);
176  ros::Publisher ret = nh.advertise<T>(topic, queue_size,
177  connect_cb,
178  disconnect_cb,
180  latch);
181  publishers_.push_back(ret);
182 
183  return ret;
184  }
185 
189  const std::string& topic,
190  int queue_size)
191  {
192  NODELET_WARN("advertiseImage with ImageTransport is deprecated");
193  return advertiseImage(nh, topic, queue_size);
194  }
195 
210  const std::string& topic,
211  int queue_size)
212  {
213  boost::mutex::scoped_lock lock(connection_mutex_);
216  this, _1);
219  this, _1);
220  bool latch;
221  nh.param("latch", latch, false);
223  topic, 1,
224  connect_cb,
225  disconnect_cb,
226  ros::VoidPtr(),
227  latch);
228  image_publishers_.push_back(pub);
229  return pub;
230  }
231 
232 
236  const std::string& topic,
237  int queue_size)
238  {
239  NODELET_WARN("advertiseCamera with ImageTransport is deprecated");
240  return advertiseCamera(nh, topic, queue_size);
241  }
242 
245  const std::string& topic,
246  int queue_size)
247  {
248  boost::mutex::scoped_lock lock(connection_mutex_);
251  this, _1);
254  this, _1);
255  ros::SubscriberStatusCallback info_connect_cb
257  this, _1);
258  ros::SubscriberStatusCallback info_disconnect_cb
260  this, _1);
261  bool latch;
262  nh.param("latch", latch, false);
265  topic, 1,
266  connect_cb, disconnect_cb,
267  info_connect_cb, info_disconnect_cb,
268  ros::VoidPtr(),
269  latch);
270  camera_publishers_.push_back(pub);
271  return pub;
272  }
273 
278  boost::mutex connection_mutex_;
279 
283  std::vector<ros::Publisher> publishers_;
284 
288  std::vector<image_transport::Publisher> image_publishers_;
289 
293  std::vector<image_transport::CameraPublisher> camera_publishers_;
294 
299 
304 
309 
315 
321 
327 
332 
337 
342 
347  private:
348 
349  };
350 }
351 
352 #endif
ConnectionStatus connection_status_
Status of connection.
image_transport::CameraPublisher advertiseCamera(ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size)
boost::shared_ptr< void const > VoidConstPtr
pub
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
#define NODELET_WARN(...)
std::vector< image_transport::Publisher > image_publishers_
List of watching image publishers.
virtual void cameraInfoConnectionCallback(const ros::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for camera info publisher ...
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ros::WallTimer timer_warn_never_subscribed_
WallTimer instance for warning about no connection.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
virtual void connectionCallback(const ros::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come
ros::Publisher advertise(ros::NodeHandle &nh, std::string topic, int queue_size)
Advertise a topic and watch the publisher. Publishers which are created by this method. It automatically reads latch boolean parameter from nh and publish topic with appropriate latch parameter.
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
image_transport::Publisher advertiseImage(ros::NodeHandle &nh, const std::string &topic, int queue_size)
Advertise an image topic and watch the publisher. Publishers which are created by this method...
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent &event)
callback function which is called when walltimer duration run out.
virtual void cameraConnectionCallback(const image_transport::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for camera image publisher ...
bool param(const std::string &param_name, T &param_val, const T &default_val) const
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
virtual void unsubscribe()=0
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
bool ever_subscribed_
A flag to check if the node has been ever subscribed or not.
image_transport::CameraPublisher advertiseCamera(ros::NodeHandle &nh, const std::string &topic, int queue_size)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual void imageConnectionCallback(const image_transport::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for image publisher
std::vector< image_transport::CameraPublisher > camera_publishers_
List of watching camera publishers.
ros::WallTimer timer_warn_on_init_post_process_called_
WallTimer instance for warning about no connection.
virtual void warnOnInitPostProcessCalledCallback(const ros::WallTimerEvent &event)
callback function which is called when walltimer duration run out.
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
ConnectionStatus
Enum to represent connection status.
virtual void cameraConnectionBaseCallback()
callback function which is called when new subscriber come for camera image publisher or camera info ...
virtual bool isSubscribed()
Returns true when this nodelet subscribes topics, false otherwise.
boost::mutex connection_mutex_
mutex to call subscribe() and unsubscribe() in critical section.
bool verbose_connection_
true if ~verbose_connection or verbose_connection parameter is true.
bool subscribed_
A flag to check if any publisher is already subscribed or not.
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
std::vector< ros::Publisher > publishers_
List of watching publishers.
image_transport::Publisher advertiseImage(ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size)
bool on_init_post_process_called_
Never warning on not calling onInitPostProcess if true.
virtual void subscribe()=0
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...


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