nodelet.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2016, Ryohei Ueda.
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/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Kei Okada 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 #ifndef OPENCV_APPS_NODELET_H_
36 #define OPENCV_APPS_NODELET_H_
37 
38 #include <ros/ros.h>
39 #include <nodelet/nodelet.h>
40 #include <boost/thread.hpp>
42 #if BOOST_VERSION < 106000 // since 1.60.0, boost uses placeholders namesapce for _1,_2...
43 #ifndef BOOST_PLAEHOLDERS
44 #define BOOST_PLAEHOLDERS
45 namespace boost
46 {
47 namespace placeholders
48 {
49 extern boost::arg<1> _1;
50 extern boost::arg<2> _2;
51 extern boost::arg<3> _3;
52 extern boost::arg<4> _4;
53 extern boost::arg<5> _5;
54 extern boost::arg<6> _6;
55 extern boost::arg<7> _7;
56 extern boost::arg<8> _8;
57 extern boost::arg<9> _9;
58 } // namespace placeholders
59 } // namespace boost
60 #endif // BOOST_PLAEHOLDERS
61 #endif // BOOST_VERSION < 106000
62 
63 // https://stackoverflow.com/questions/10496824/how-to-define-nullptr-for-supporting-both-c03-and-c11
64 #if !defined(nullptr)
65 #define nullptr NULL
66 #endif
67 
68 namespace opencv_apps
69 {
74 {
78 };
79 
90 class Nodelet : public nodelet::Nodelet
91 {
92 public:
93  Nodelet() : subscribed_(false)
94  {
95  }
96 
97 protected:
102  virtual void onInit();
103 
109  virtual void onInitPostProcess();
110 
114  virtual void connectionCallback(const ros::SingleSubscriberPublisher& pub);
115 
120  virtual void imageConnectionCallback(const image_transport::SingleSubscriberPublisher& pub);
121 
126  virtual void cameraConnectionCallback(const image_transport::SingleSubscriberPublisher& pub);
127 
132  virtual void cameraInfoConnectionCallback(const ros::SingleSubscriberPublisher& pub);
133 
140  virtual void cameraConnectionBaseCallback();
141 
146  virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent& event);
147 
153  virtual void subscribe() = 0;
154 
160  virtual void unsubscribe() = 0;
161 
174  template <class T>
175  ros::Publisher advertise(ros::NodeHandle& nh, std::string topic, int queue_size)
176  {
177  boost::mutex::scoped_lock lock(connection_mutex_);
178  ros::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::connectionCallback, this, boost::placeholders::_1);
179  ros::SubscriberStatusCallback disconnect_cb =
180  boost::bind(&Nodelet::connectionCallback, this, boost::placeholders::_1);
181  bool latch;
182  nh.param("latch", latch, false);
183  ros::Publisher ret = nh.advertise<T>(topic, queue_size, connect_cb, disconnect_cb, ros::VoidConstPtr(), latch);
184  publishers_.push_back(ret);
185 
186  return ret;
187  }
188 
201  image_transport::Publisher advertiseImage(ros::NodeHandle& nh, const std::string& topic, int queue_size)
202  {
203  boost::mutex::scoped_lock lock(connection_mutex_);
205  boost::bind(&Nodelet::imageConnectionCallback, this, boost::placeholders::_1);
207  boost::bind(&Nodelet::imageConnectionCallback, this, boost::placeholders::_1);
208  bool latch;
209  nh.param("latch", latch, false);
211  image_transport::ImageTransport(nh).advertise(topic, 1, connect_cb, disconnect_cb, ros::VoidPtr(), latch);
212  image_publishers_.push_back(pub);
213  return pub;
214  }
215 
229  image_transport::CameraPublisher advertiseCamera(ros::NodeHandle& nh, const std::string& topic, int queue_size)
230  {
231  boost::mutex::scoped_lock lock(connection_mutex_);
233  boost::bind(&Nodelet::cameraConnectionCallback, this, boost::placeholders::_1);
235  boost::bind(&Nodelet::cameraConnectionCallback, this, boost::placeholders::_1);
236  ros::SubscriberStatusCallback info_connect_cb =
237  boost::bind(&Nodelet::cameraInfoConnectionCallback, this, boost::placeholders::_1);
238  ros::SubscriberStatusCallback info_disconnect_cb =
239  boost::bind(&Nodelet::cameraInfoConnectionCallback, this, boost::placeholders::_1);
240  bool latch;
241  nh.param("latch", latch, false);
243  topic, 1, connect_cb, disconnect_cb, info_connect_cb, info_disconnect_cb, ros::VoidPtr(), latch);
244  camera_publishers_.push_back(pub);
245  return pub;
246  }
247 
252  boost::mutex connection_mutex_;
253 
257  std::vector<ros::Publisher> publishers_;
258 
262  std::vector<image_transport::Publisher> image_publishers_;
263 
267  std::vector<image_transport::CameraPublisher> camera_publishers_;
268 
273 
278 
283 
289 
295 
301 
306 
311 
312 private:
313 };
314 } // namespace opencv_apps
315 
316 #endif
boost::shared_ptr< void const > VoidConstPtr
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
bool verbose_connection_
true if ~verbose_connection or verbose_connection parameter is true.
Definition: nodelet.h:310
boost::arg< 4 > _4
Definition: nodelet.cpp:47
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Definition: nodelet.h:90
Demo code to calculate moments.
Definition: nodelet.h:68
boost::arg< 2 > _2
Definition: nodelet.cpp:45
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::arg< 9 > _9
Definition: nodelet.cpp:52
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:277
ros::WallTimer timer_
WallTimer instance for warning about no connection.
Definition: nodelet.h:282
std::vector< image_transport::Publisher > image_publishers_
List of watching image publishers.
Definition: nodelet.h:262
void subscribe()
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:300
boost::arg< 3 > _3
Definition: nodelet.cpp:46
boost::arg< 7 > _7
Definition: nodelet.cpp:50
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:272
boost::arg< 6 > _6
Definition: nodelet.cpp:49
boost::arg< 1 > _1
Definition: nodelet.cpp:44
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ConnectionStatus
Enum to represent connection status.
Definition: nodelet.h:73
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...
Definition: nodelet.h:201
image_transport::CameraPublisher advertiseCamera(ros::NodeHandle &nh, const std::string &topic, int queue_size)
Advertise an image topic camera info topic and watch the publisher. Publishers which are created by t...
Definition: nodelet.h:229
ConnectionStatus connection_status_
Status of connection.
Definition: nodelet.h:305
bool ever_subscribed_
A flag to check if the node has been ever subscribed or not.
Definition: nodelet.h:294
bool subscribed_
A flag to check if any publisher is already subscribed or not.
Definition: nodelet.h:288
boost::arg< 8 > _8
Definition: nodelet.cpp:51
void unsubscribe()
boost::arg< 5 > _5
Definition: nodelet.cpp:48
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.
Definition: nodelet.h:175
boost::mutex connection_mutex_
mutex to call subscribe() and unsubscribe() in critical section.
Definition: nodelet.h:252
std::vector< image_transport::CameraPublisher > camera_publishers_
List of watching camera publishers.
Definition: nodelet.h:267
std::vector< ros::Publisher > publishers_
List of watching publishers.
Definition: nodelet.h:257


opencv_apps
Author(s): Kei Okada
autogenerated on Thu Feb 2 2023 03:40:24