connection_based_nodelet.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 
00037 #ifndef CONNECTION_BASED_NODELET_H_
00038 #define CONNECTION_BASED_NODELET_H_
00039 
00040 #include <ros/ros.h>
00041 #include <nodelet/nodelet.h>
00042 #include <boost/thread.hpp>
00043 #include <image_transport/image_transport.h>
00044 #include "jsk_topic_tools/log_utils.h"
00045 
00046 namespace jsk_topic_tools
00047 {
00051   enum ConnectionStatus
00052   {
00053     NOT_INITIALIZED,
00054     NOT_SUBSCRIBED,
00055     SUBSCRIBED
00056   };
00057   
00068   class ConnectionBasedNodelet: public nodelet::Nodelet
00069   {
00070   public:
00071     ConnectionBasedNodelet(): subscribed_(false) { }
00072   protected:
00073     
00078     virtual void onInit();
00079 
00080 
00086     virtual void onInitPostProcess();
00087     
00091     virtual void connectionCallback(const ros::SingleSubscriberPublisher& pub);
00092 
00097     virtual void imageConnectionCallback(
00098       const image_transport::SingleSubscriberPublisher& pub);
00099 
00104     virtual void cameraConnectionCallback(
00105       const image_transport::SingleSubscriberPublisher& pub);
00106     
00111     virtual void cameraInfoConnectionCallback(
00112       const ros::SingleSubscriberPublisher& pub);
00113     
00120     virtual void cameraConnectionBaseCallback();
00121 
00126     virtual void warnOnInitPostProcessCalledCallback(const ros::WallTimerEvent& event);
00127 
00132     virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent& event);
00133 
00139     virtual void subscribe() = 0;
00140 
00146     virtual void unsubscribe() = 0;
00147 
00151     virtual bool isSubscribed();
00152 
00165     template<class T> ros::Publisher
00166     advertise(ros::NodeHandle& nh,
00167               std::string topic, int queue_size)
00168     {
00169       boost::mutex::scoped_lock lock(connection_mutex_);
00170       ros::SubscriberStatusCallback connect_cb
00171         = boost::bind(&ConnectionBasedNodelet::connectionCallback, this, _1);
00172       ros::SubscriberStatusCallback disconnect_cb
00173         = boost::bind(&ConnectionBasedNodelet::connectionCallback, this, _1);
00174       bool latch;
00175       nh.param("latch", latch, false);
00176       ros::Publisher ret = nh.advertise<T>(topic, queue_size,
00177                                            connect_cb,
00178                                            disconnect_cb,
00179                                            ros::VoidConstPtr(),
00180                                            latch);
00181       publishers_.push_back(ret);
00182       
00183       return ret;
00184     }
00185 
00186     image_transport::Publisher
00187     advertiseImage(ros::NodeHandle& nh,
00188                    image_transport::ImageTransport& it,
00189                    const std::string& topic,
00190                    int queue_size)
00191     {
00192       NODELET_WARN("advertiseImage with ImageTransport is deprecated");
00193       return advertiseImage(nh, topic, queue_size);
00194     }
00195     
00208     image_transport::Publisher
00209     advertiseImage(ros::NodeHandle& nh,
00210                    const std::string& topic,
00211                    int queue_size)
00212     {
00213       boost::mutex::scoped_lock lock(connection_mutex_);
00214       image_transport::SubscriberStatusCallback connect_cb
00215         = boost::bind(&ConnectionBasedNodelet::imageConnectionCallback,
00216                       this, _1);
00217       image_transport::SubscriberStatusCallback disconnect_cb
00218         = boost::bind(&ConnectionBasedNodelet::imageConnectionCallback,
00219                       this, _1);
00220       bool latch;
00221       nh.param("latch", latch, false);
00222       image_transport::Publisher pub = image_transport::ImageTransport(nh).advertise(
00223         topic, 1,
00224         connect_cb,
00225         disconnect_cb,
00226         ros::VoidPtr(),
00227         latch);
00228       image_publishers_.push_back(pub);
00229       return pub;
00230     }
00231 
00232 
00233     image_transport::CameraPublisher
00234     advertiseCamera(ros::NodeHandle& nh,
00235                     image_transport::ImageTransport& it,
00236                     const std::string& topic,
00237                     int queue_size)
00238     {
00239       NODELET_WARN("advertiseCamera with ImageTransport is deprecated");
00240       return advertiseCamera(nh, topic, queue_size);
00241     }
00242     
00243     image_transport::CameraPublisher
00244     advertiseCamera(ros::NodeHandle& nh,
00245                     const std::string& topic,
00246                     int queue_size)
00247     {
00248       boost::mutex::scoped_lock lock(connection_mutex_);
00249       image_transport::SubscriberStatusCallback connect_cb
00250         = boost::bind(&ConnectionBasedNodelet::cameraConnectionCallback,
00251                       this, _1);
00252       image_transport::SubscriberStatusCallback disconnect_cb
00253         = boost::bind(&ConnectionBasedNodelet::cameraConnectionCallback,
00254                       this, _1);
00255       ros::SubscriberStatusCallback info_connect_cb
00256         = boost::bind(&ConnectionBasedNodelet::cameraInfoConnectionCallback,
00257                       this, _1);
00258       ros::SubscriberStatusCallback info_disconnect_cb
00259         = boost::bind(&ConnectionBasedNodelet::cameraInfoConnectionCallback,
00260                       this, _1);
00261       bool latch;
00262       nh.param("latch", latch, false);
00263       image_transport::CameraPublisher
00264         pub = image_transport::ImageTransport(nh).advertiseCamera(
00265           topic, 1,
00266           connect_cb, disconnect_cb,
00267           info_connect_cb, info_disconnect_cb,
00268           ros::VoidPtr(),
00269           latch);
00270       camera_publishers_.push_back(pub);
00271       return pub;
00272     }
00273     
00278     boost::mutex connection_mutex_;
00279     
00283     std::vector<ros::Publisher> publishers_;
00284 
00288     std::vector<image_transport::Publisher> image_publishers_;
00289 
00293     std::vector<image_transport::CameraPublisher> camera_publishers_;
00294 
00298     boost::shared_ptr<ros::NodeHandle> nh_;
00299 
00303     boost::shared_ptr<ros::NodeHandle> pnh_;
00304 
00308     ros::WallTimer timer_warn_never_subscribed_;
00309 
00314     bool subscribed_;
00315 
00320     bool ever_subscribed_;
00321 
00326     bool always_subscribe_;
00327 
00331     ConnectionStatus connection_status_;
00332 
00336     bool verbose_connection_;
00337 
00341     bool on_init_post_process_called_;
00342 
00346     ros::WallTimer timer_warn_on_init_post_process_called_;
00347   private:
00348     
00349   };
00350 }
00351 
00352 #endif


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Fri Sep 8 2017 03:38:56