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 
38 namespace opencv_apps
39 {
41 {
43  nh_.reset(new ros::NodeHandle(getMTNodeHandle()));
45  pnh_->param("always_subscribe", always_subscribe_, false);
46  pnh_->param("verbose_connection", verbose_connection_, false);
48  {
49  nh_->param("verbose_connection", verbose_connection_, false);
50  }
51  // timer to warn when no connection in a few seconds
52  ever_subscribed_ = false;
54  /*oneshot=*/true);
55 }
56 
58 {
60  {
61  subscribe();
62  }
63 }
64 
66 {
67  if (!ever_subscribed_)
68  {
69  NODELET_WARN("'%s' subscribes topics only with child subscribers.", nodelet::Nodelet::getName().c_str());
70  }
71 }
72 
74 {
76  {
77  NODELET_INFO("New connection or disconnection is detected");
78  }
79  if (!always_subscribe_)
80  {
81  boost::mutex::scoped_lock lock(connection_mutex_);
82  for (const ros::Publisher& pub : publishers_)
83  {
84  if (pub.getNumSubscribers() > 0)
85  {
86  if (!ever_subscribed_)
87  {
88  ever_subscribed_ = true;
89  }
91  {
93  {
94  NODELET_INFO("Subscribe input topics");
95  }
96  subscribe();
98  }
99  return;
100  }
101  }
103  {
105  {
106  NODELET_INFO("Unsubscribe input topics");
107  }
108  unsubscribe();
110  }
111  }
112 }
113 
115 {
117  {
118  NODELET_INFO("New image connection or disconnection is detected");
119  }
120  if (!always_subscribe_)
121  {
122  boost::mutex::scoped_lock lock(connection_mutex_);
124  {
125  if (pub.getNumSubscribers() > 0)
126  {
127  if (!ever_subscribed_)
128  {
129  ever_subscribed_ = true;
130  }
132  {
134  {
135  NODELET_INFO("Subscribe input topics");
136  }
137  subscribe();
139  }
140  return;
141  }
142  }
144  {
146  {
147  NODELET_INFO("Unsubscribe input topics");
148  }
149  unsubscribe();
151  }
152  }
153 }
154 
156 {
158 }
159 
161 {
163 }
164 
166 {
168  {
169  NODELET_INFO("New image connection or disconnection is detected");
170  }
171  if (!always_subscribe_)
172  {
173  boost::mutex::scoped_lock lock(connection_mutex_);
175  {
176  if (pub.getNumSubscribers() > 0)
177  {
178  if (!ever_subscribed_)
179  {
180  ever_subscribed_ = true;
181  }
183  {
185  {
186  NODELET_INFO("Subscribe input topics");
187  }
188  subscribe();
190  }
191  return;
192  }
193  }
195  {
197  {
198  NODELET_INFO("Unsubscribe input topics");
199  }
200  unsubscribe();
202  }
203  }
204 }
205 } // namespace opencv_apps
bool verbose_connection_
true if ~verbose_connection or verbose_connection parameter is true.
Definition: nodelet.h:283
#define NODELET_WARN(...)
virtual void imageConnectionCallback(const image_transport::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for image publisher
Definition: nodelet.cpp:114
Demo code to calculate moments.
Definition: nodelet.h:48
const std::string & getName() const
ros::NodeHandle & getMTNodeHandle() const
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:250
virtual void unsubscribe()=0
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
virtual void cameraConnectionBaseCallback()
callback function which is called when new subscriber come for camera image publisher or camera info ...
Definition: nodelet.cpp:165
virtual void subscribe()=0
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
ros::WallTimer timer_
WallTimer instance for warning about no connection.
Definition: nodelet.h:255
std::vector< image_transport::Publisher > image_publishers_
List of watching image publishers.
Definition: nodelet.h:235
ros::NodeHandle & getMTPrivateNodeHandle() const
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:273
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
Definition: nodelet.cpp:57
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
Definition: nodelet.cpp:40
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:245
virtual void cameraInfoConnectionCallback(const ros::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for camera info publisher ...
Definition: nodelet.cpp:160
virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent &event)
callback function which is called when walltimer duration run out.
Definition: nodelet.cpp:65
ConnectionStatus connection_status_
Status of connection.
Definition: nodelet.h:278
#define NODELET_INFO(...)
bool ever_subscribed_
A flag to check if the node has been ever subscribed or not.
Definition: nodelet.h:267
virtual void cameraConnectionCallback(const image_transport::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for camera image publisher ...
Definition: nodelet.cpp:155
boost::mutex connection_mutex_
mutex to call subscribe() and unsubscribe() in critical section.
Definition: nodelet.h:225
std::vector< image_transport::CameraPublisher > camera_publishers_
List of watching camera publishers.
Definition: nodelet.h:240
virtual void connectionCallback(const ros::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come
Definition: nodelet.cpp:73
std::vector< ros::Publisher > publishers_
List of watching publishers.
Definition: nodelet.h:230


opencv_apps
Author(s): Kei Okada
autogenerated on Sat Aug 22 2020 03:35:08