nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016, Ryohei Ueda.
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 #include "opencv_apps/nodelet.h"
37 #if BOOST_VERSION < 106000 // since 1.60.0, boost uses placeholders namesapce for _1,_2...
38 #ifndef BOOST_PLAEHOLDERS
39 #define BOOST_PLAEHOLDERS
40 namespace boost
41 {
42 namespace placeholders
43 {
44 boost::arg<1> _1;
45 boost::arg<2> _2;
46 boost::arg<3> _3;
47 boost::arg<4> _4;
48 boost::arg<5> _5;
49 boost::arg<6> _6;
50 boost::arg<7> _7;
51 boost::arg<8> _8;
52 boost::arg<9> _9;
53 } // namespace placeholders
54 } // namespace boost
55 #endif // BOOST_PLAEHOLDERS
56 #endif // BOOST_VERSION < 106000
57 
58 namespace opencv_apps
59 {
61 {
63  nh_.reset(new ros::NodeHandle(getMTNodeHandle()));
65  pnh_->param("always_subscribe", always_subscribe_, false);
66  pnh_->param("verbose_connection", verbose_connection_, false);
68  {
69  nh_->param("verbose_connection", verbose_connection_, false);
70  }
71  // timer to warn when no connection in a few seconds
72  ever_subscribed_ = false;
74  /*oneshot=*/true);
75 }
76 
78 {
80  {
81  subscribe();
82  }
83 }
84 
86 {
87  if (!ever_subscribed_)
88  {
89  NODELET_WARN("'%s' subscribes topics only with child subscribers.", nodelet::Nodelet::getName().c_str());
90  }
91 }
92 
94 {
96  {
97  NODELET_INFO("New connection or disconnection is detected");
98  }
99  if (!always_subscribe_)
100  {
101  boost::mutex::scoped_lock lock(connection_mutex_);
102  for (const ros::Publisher& pub : publishers_)
103  {
104  if (pub.getNumSubscribers() > 0)
105  {
106  if (!ever_subscribed_)
107  {
108  ever_subscribed_ = true;
109  }
111  {
113  {
114  NODELET_INFO("Subscribe input topics");
115  }
116  subscribe();
118  }
119  return;
120  }
121  }
123  {
125  {
126  NODELET_INFO("Unsubscribe input topics");
127  }
128  unsubscribe();
130  }
131  }
132 }
133 
135 {
137  {
138  NODELET_INFO("New image connection or disconnection is detected");
139  }
140  if (!always_subscribe_)
141  {
142  boost::mutex::scoped_lock lock(connection_mutex_);
144  {
145  if (pub.getNumSubscribers() > 0)
146  {
147  if (!ever_subscribed_)
148  {
149  ever_subscribed_ = true;
150  }
152  {
154  {
155  NODELET_INFO("Subscribe input topics");
156  }
157  subscribe();
159  }
160  return;
161  }
162  }
164  {
166  {
167  NODELET_INFO("Unsubscribe input topics");
168  }
169  unsubscribe();
171  }
172  }
173 }
174 
176 {
178 }
179 
181 {
183 }
184 
186 {
188  {
189  NODELET_INFO("New image connection or disconnection is detected");
190  }
191  if (!always_subscribe_)
192  {
193  boost::mutex::scoped_lock lock(connection_mutex_);
195  {
196  if (pub.getNumSubscribers() > 0)
197  {
198  if (!ever_subscribed_)
199  {
200  ever_subscribed_ = true;
201  }
203  {
205  {
206  NODELET_INFO("Subscribe input topics");
207  }
208  subscribe();
210  }
211  return;
212  }
213  }
215  {
217  {
218  NODELET_INFO("Unsubscribe input topics");
219  }
220  unsubscribe();
222  }
223  }
224 }
225 } // namespace opencv_apps
nodelet.h
opencv_apps::Nodelet::onInitPostProcess
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
Definition: nodelet.cpp:77
ros::Publisher
boost::placeholders::_4
boost::arg< 4 > _4
Definition: nodelet.cpp:47
opencv_apps::Nodelet::connection_status_
ConnectionStatus connection_status_
Status of connection.
Definition: nodelet.h:305
opencv_apps::Nodelet::image_publishers_
std::vector< image_transport::Publisher > image_publishers_
List of watching image publishers.
Definition: nodelet.h:262
boost::placeholders::_1
boost::arg< 1 > _1
Definition: nodelet.cpp:44
opencv_apps::Nodelet::publishers_
std::vector< ros::Publisher > publishers_
List of watching publishers.
Definition: nodelet.h:257
nodelet::Nodelet::getMTPrivateNodeHandle
ros::NodeHandle & getMTPrivateNodeHandle() const
NODELET_WARN
#define NODELET_WARN(...)
boost
image_transport::SingleSubscriberPublisher::getNumSubscribers
uint32_t getNumSubscribers() const
opencv_apps::Nodelet::connectionCallback
virtual void connectionCallback(const ros::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come
Definition: nodelet.cpp:93
boost::placeholders::_3
boost::arg< 3 > _3
Definition: nodelet.cpp:46
opencv_apps::Nodelet::cameraInfoConnectionCallback
virtual void cameraInfoConnectionCallback(const ros::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for camera info publisher
Definition: nodelet.cpp:180
opencv_apps::Nodelet::timer_
ros::WallTimer timer_
WallTimer instance for warning about no connection.
Definition: nodelet.h:282
ros::SingleSubscriberPublisher
opencv_apps::Nodelet::cameraConnectionCallback
virtual void cameraConnectionCallback(const image_transport::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for camera image publisher
Definition: nodelet.cpp:175
opencv_apps::Nodelet::unsubscribe
virtual void unsubscribe()=0
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
boost::placeholders::_6
boost::arg< 6 > _6
Definition: nodelet.cpp:49
boost::placeholders::_5
boost::arg< 5 > _5
Definition: nodelet.cpp:48
opencv_apps::Nodelet::imageConnectionCallback
virtual void imageConnectionCallback(const image_transport::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for image publisher
Definition: nodelet.cpp:134
opencv_apps::Nodelet::warnNeverSubscribedCallback
virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent &event)
callback function which is called when walltimer duration run out.
Definition: nodelet.cpp:85
boost::placeholders::_7
boost::arg< 7 > _7
Definition: nodelet.cpp:50
boost::placeholders::_2
boost::arg< 2 > _2
Definition: nodelet.cpp:45
opencv_apps::Nodelet::always_subscribe_
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:300
opencv_apps::Nodelet::verbose_connection_
bool verbose_connection_
true if ~verbose_connection or verbose_connection parameter is true.
Definition: nodelet.h:310
image_transport::CameraPublisher
opencv_apps::NOT_SUBSCRIBED
@ NOT_SUBSCRIBED
Definition: nodelet.h:76
opencv_apps
Demo code to calculate moments.
Definition: nodelet.h:68
image_transport::SingleSubscriberPublisher
NODELET_INFO
#define NODELET_INFO(...)
boost::placeholders::_8
boost::arg< 8 > _8
Definition: nodelet.cpp:51
boost::placeholders::_9
boost::arg< 9 > _9
Definition: nodelet.cpp:52
ros::WallTimerEvent
opencv_apps::Nodelet::cameraConnectionBaseCallback
virtual void cameraConnectionBaseCallback()
callback function which is called when new subscriber come for camera image publisher or camera info ...
Definition: nodelet.cpp:185
opencv_apps::Nodelet::camera_publishers_
std::vector< image_transport::CameraPublisher > camera_publishers_
List of watching camera publishers.
Definition: nodelet.h:267
image_transport::Publisher
opencv_apps::Nodelet::subscribe
virtual void subscribe()=0
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
opencv_apps::Nodelet::ever_subscribed_
bool ever_subscribed_
A flag to check if the node has been ever subscribed or not.
Definition: nodelet.h:294
nodelet::Nodelet::getName
const std::string & getName() const
opencv_apps::SUBSCRIBED
@ SUBSCRIBED
Definition: nodelet.h:77
ros::WallDuration
opencv_apps::Nodelet::nh_
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:272
opencv_apps::Nodelet::connection_mutex_
boost::mutex connection_mutex_
mutex to call subscribe() and unsubscribe() in critical section.
Definition: nodelet.h:252
ros::NodeHandle
opencv_apps::Nodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: nodelet.cpp:60
opencv_apps::Nodelet::pnh_
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:277
nodelet::Nodelet::getMTNodeHandle
ros::NodeHandle & getMTNodeHandle() const


opencv_apps
Author(s): Kei Okada
autogenerated on Fri May 23 2025 02:49:49