nodelet.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2016, Ryohei Ueda.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Kei Okada nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #ifndef OPENCV_APPS_NODELET_H_
00036 #define OPENCV_APPS_NODELET_H_
00037 
00038 #include <ros/ros.h>
00039 #include <nodelet/nodelet.h>
00040 #include <boost/thread.hpp>
00041 #include <image_transport/image_transport.h>
00042 
00043 // https://stackoverflow.com/questions/10496824/how-to-define-nullptr-for-supporting-both-c03-and-c11
00044 #if !defined(nullptr)
00045 #define nullptr NULL
00046 #endif
00047 
00048 namespace opencv_apps
00049 {
00053 enum ConnectionStatus
00054 {
00055   NOT_INITIALIZED,
00056   NOT_SUBSCRIBED,
00057   SUBSCRIBED
00058 };
00059 
00070 class Nodelet : public nodelet::Nodelet
00071 {
00072 public:
00073   Nodelet() : subscribed_(false)
00074   {
00075   }
00076 
00077 protected:
00082   virtual void onInit();
00083 
00089   virtual void onInitPostProcess();
00090 
00094   virtual void connectionCallback(const ros::SingleSubscriberPublisher& pub);
00095 
00100   virtual void imageConnectionCallback(const image_transport::SingleSubscriberPublisher& pub);
00101 
00106   virtual void cameraConnectionCallback(const image_transport::SingleSubscriberPublisher& pub);
00107 
00112   virtual void cameraInfoConnectionCallback(const ros::SingleSubscriberPublisher& pub);
00113 
00120   virtual void cameraConnectionBaseCallback();
00121 
00126   virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent& event);
00127 
00133   virtual void subscribe() = 0;
00134 
00140   virtual void unsubscribe() = 0;
00141 
00154   template <class T>
00155   ros::Publisher advertise(ros::NodeHandle& nh, std::string topic, int queue_size)
00156   {
00157     boost::mutex::scoped_lock lock(connection_mutex_);
00158     ros::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::connectionCallback, this, _1);
00159     ros::SubscriberStatusCallback disconnect_cb = boost::bind(&Nodelet::connectionCallback, this, _1);
00160     bool latch;
00161     nh.param("latch", latch, false);
00162     ros::Publisher ret = nh.advertise<T>(topic, queue_size, connect_cb, disconnect_cb, ros::VoidConstPtr(), latch);
00163     publishers_.push_back(ret);
00164 
00165     return ret;
00166   }
00167 
00180   image_transport::Publisher advertiseImage(ros::NodeHandle& nh, const std::string& topic, int queue_size)
00181   {
00182     boost::mutex::scoped_lock lock(connection_mutex_);
00183     image_transport::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::imageConnectionCallback, this, _1);
00184     image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&Nodelet::imageConnectionCallback, this, _1);
00185     bool latch;
00186     nh.param("latch", latch, false);
00187     image_transport::Publisher pub =
00188         image_transport::ImageTransport(nh).advertise(topic, 1, connect_cb, disconnect_cb, ros::VoidPtr(), latch);
00189     image_publishers_.push_back(pub);
00190     return pub;
00191   }
00192 
00206   image_transport::CameraPublisher advertiseCamera(ros::NodeHandle& nh, const std::string& topic, int queue_size)
00207   {
00208     boost::mutex::scoped_lock lock(connection_mutex_);
00209     image_transport::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::cameraConnectionCallback, this, _1);
00210     image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&Nodelet::cameraConnectionCallback, this, _1);
00211     ros::SubscriberStatusCallback info_connect_cb = boost::bind(&Nodelet::cameraInfoConnectionCallback, this, _1);
00212     ros::SubscriberStatusCallback info_disconnect_cb = boost::bind(&Nodelet::cameraInfoConnectionCallback, this, _1);
00213     bool latch;
00214     nh.param("latch", latch, false);
00215     image_transport::CameraPublisher pub = image_transport::ImageTransport(nh).advertiseCamera(
00216         topic, 1, connect_cb, disconnect_cb, info_connect_cb, info_disconnect_cb, ros::VoidPtr(), latch);
00217     camera_publishers_.push_back(pub);
00218     return pub;
00219   }
00220 
00225   boost::mutex connection_mutex_;
00226 
00230   std::vector<ros::Publisher> publishers_;
00231 
00235   std::vector<image_transport::Publisher> image_publishers_;
00236 
00240   std::vector<image_transport::CameraPublisher> camera_publishers_;
00241 
00245   boost::shared_ptr<ros::NodeHandle> nh_;
00246 
00250   boost::shared_ptr<ros::NodeHandle> pnh_;
00251 
00255   ros::WallTimer timer_;
00256 
00261   bool subscribed_;
00262 
00267   bool ever_subscribed_;
00268 
00273   bool always_subscribe_;
00274 
00278   ConnectionStatus connection_status_;
00279 
00283   bool verbose_connection_;
00284 
00285 private:
00286 };
00287 }
00288 
00289 #endif


opencv_apps
Author(s): Kei Okada
autogenerated on Mon Apr 22 2019 02:18:26