1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289
|
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2016, Ryohei Ueda.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Kei Okada nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
#ifndef OPENCV_APPS_NODELET_H_
#define OPENCV_APPS_NODELET_H_
#include <ros/ros.h>
#include <nodelet/nodelet.h>
#include <boost/thread.hpp>
#include <image_transport/image_transport.h>
// https://stackoverflow.com/questions/10496824/how-to-define-nullptr-for-supporting-both-c03-and-c11
#if !defined(nullptr)
#define nullptr NULL
#endif
namespace opencv_apps
{
/** @brief
* Enum to represent connection status.
*/
enum ConnectionStatus
{
NOT_INITIALIZED,
NOT_SUBSCRIBED,
SUBSCRIBED
};
/** @brief
* Nodelet to automatically subscribe/unsubscribe
* topics according to subscription of advertised topics.
*
* It's important not to subscribe topic if no output is required.
*
* In order to watch advertised topics, need to use advertise template method.
* And create subscribers in subscribe() and shutdown them in unsubscribed().
*
*/
class Nodelet : public nodelet::Nodelet
{
public:
Nodelet() : subscribed_(false)
{
}
protected:
/** @brief
* Initialize nodehandles nh_ and pnh_. Subclass should call
* this method in its onInit method
*/
virtual void onInit();
/** @brief
* Post processing of initialization of nodelet.
* You need to call this method in order to use always_subscribe
* feature.
*/
virtual void onInitPostProcess();
/** @brief
* callback function which is called when new subscriber come
*/
virtual void connectionCallback(const ros::SingleSubscriberPublisher& pub);
/** @brief
* callback function which is called when new subscriber come for image
* publisher
*/
virtual void imageConnectionCallback(const image_transport::SingleSubscriberPublisher& pub);
/** @brief
* callback function which is called when new subscriber come for camera
* image publisher
*/
virtual void cameraConnectionCallback(const image_transport::SingleSubscriberPublisher& pub);
/** @brief
* callback function which is called when new subscriber come for
* camera info publisher
*/
virtual void cameraInfoConnectionCallback(const ros::SingleSubscriberPublisher& pub);
/** @brief
* callback function which is called when new subscriber come for camera
* image publisher or camera info publisher.
* This function is called from cameraConnectionCallback
* or cameraInfoConnectionCallback.
*/
virtual void cameraConnectionBaseCallback();
/** @brief
* callback function which is called when walltimer
* duration run out.
*/
virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent& event);
/** @brief
* This method is called when publisher is subscribed by other
* nodes.
* Set up subscribers in this method.
*/
virtual void subscribe() = 0;
/** @brief
* This method is called when publisher is unsubscribed by other
* nodes.
* Shut down subscribers in this method.
*/
virtual void unsubscribe() = 0;
/** @brief
* 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.
*
* @param nh NodeHandle.
* @param topic topic name to advertise.
* @param queue_size queue size for publisher.
* @param latch set true if latch topic publication.
* @return Publisher for the advertised topic.
*/
template <class T>
ros::Publisher advertise(ros::NodeHandle& nh, std::string topic, int queue_size)
{
boost::mutex::scoped_lock lock(connection_mutex_);
ros::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::connectionCallback, this, boost::placeholders::_1);
ros::SubscriberStatusCallback disconnect_cb = boost::bind(&Nodelet::connectionCallback, this, boost::placeholders::_1);
bool latch;
nh.param("latch", latch, false);
ros::Publisher ret = nh.advertise<T>(topic, queue_size, connect_cb, disconnect_cb, ros::VoidConstPtr(), latch);
publishers_.push_back(ret);
return ret;
}
/** @brief
* Advertise an image topic and watch the publisher. Publishers which are
* created by this method.
* It automatically reads latch boolean parameter from nh and it and
* publish topic with appropriate latch parameter.
*
* @param nh NodeHandle.
* @param topic topic name to advertise.
* @param queue_size queue size for publisher.
* @param latch set true if latch topic publication.
* @return Publisher for the advertised topic.
*/
image_transport::Publisher advertiseImage(ros::NodeHandle& nh, const std::string& topic, int queue_size)
{
boost::mutex::scoped_lock lock(connection_mutex_);
image_transport::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::imageConnectionCallback, this, boost::placeholders::_1);
image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&Nodelet::imageConnectionCallback, this, boost::placeholders::_1);
bool latch;
nh.param("latch", latch, false);
image_transport::Publisher pub =
image_transport::ImageTransport(nh).advertise(topic, 1, connect_cb, disconnect_cb, ros::VoidPtr(), latch);
image_publishers_.push_back(pub);
return pub;
}
/** @brief
* Advertise an image topic camera info topic and watch the publisher.
* Publishers which are
* created by this method.
* It automatically reads latch boolean parameter from nh and it and
* publish topic with appropriate latch parameter.
*
* @param nh NodeHandle.
* @param topic topic name to advertise.
* @param queue_size queue size for publisher.
* @param latch set true if latch topic publication.
* @return Publisher for the advertised topic.
*/
image_transport::CameraPublisher advertiseCamera(ros::NodeHandle& nh, const std::string& topic, int queue_size)
{
boost::mutex::scoped_lock lock(connection_mutex_);
image_transport::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::cameraConnectionCallback, this, boost::placeholders::_1);
image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&Nodelet::cameraConnectionCallback, this, boost::placeholders::_1);
ros::SubscriberStatusCallback info_connect_cb = boost::bind(&Nodelet::cameraInfoConnectionCallback, this, boost::placeholders::_1);
ros::SubscriberStatusCallback info_disconnect_cb = boost::bind(&Nodelet::cameraInfoConnectionCallback, this, boost::placeholders::_1);
bool latch;
nh.param("latch", latch, false);
image_transport::CameraPublisher pub = image_transport::ImageTransport(nh).advertiseCamera(
topic, 1, connect_cb, disconnect_cb, info_connect_cb, info_disconnect_cb, ros::VoidPtr(), latch);
camera_publishers_.push_back(pub);
return pub;
}
/** @brief
* mutex to call subscribe() and unsubscribe() in
* critical section.
*/
boost::mutex connection_mutex_;
/** @brief
* List of watching publishers
*/
std::vector<ros::Publisher> publishers_;
/** @brief
* List of watching image publishers
*/
std::vector<image_transport::Publisher> image_publishers_;
/** @brief
* List of watching camera publishers
*/
std::vector<image_transport::CameraPublisher> camera_publishers_;
/** @brief
* Shared pointer to nodehandle.
*/
boost::shared_ptr<ros::NodeHandle> nh_;
/** @brief
* Shared pointer to private nodehandle.
*/
boost::shared_ptr<ros::NodeHandle> pnh_;
/** @brief
* WallTimer instance for warning about no connection.
*/
ros::WallTimer timer_;
/** @brief
* A flag to check if any publisher is already subscribed
* or not.
*/
bool subscribed_;
/** @brief
* A flag to check if the node has been ever subscribed
* or not.
*/
bool ever_subscribed_;
/** @brief
* A flag to disable watching mechanism and always subscribe input
* topics. It can be specified via ~always_subscribe parameter.
*/
bool always_subscribe_;
/** @brief
* Status of connection
*/
ConnectionStatus connection_status_;
/** @brief
* true if `~verbose_connection` or `verbose_connection` parameter is true.
*/
bool verbose_connection_;
private:
};
}
#endif
|