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 namespace opencv_apps
00044 {
00048   enum ConnectionStatus
00049   {
00050     NOT_INITIALIZED,
00051     NOT_SUBSCRIBED,
00052     SUBSCRIBED
00053   };
00054   
00065   class Nodelet: public nodelet::Nodelet
00066   {
00067   public:
00068     Nodelet(): subscribed_(false) { }
00069   protected:
00070     
00075     virtual void onInit();
00076 
00077 
00083     virtual void onInitPostProcess();
00084     
00088     virtual void connectionCallback(const ros::SingleSubscriberPublisher& pub);
00089 
00094     virtual void imageConnectionCallback(
00095       const image_transport::SingleSubscriberPublisher& pub);
00096 
00101     virtual void cameraConnectionCallback(
00102       const image_transport::SingleSubscriberPublisher& pub);
00103     
00108     virtual void cameraInfoConnectionCallback(
00109       const ros::SingleSubscriberPublisher& pub);
00110     
00117     virtual void cameraConnectionBaseCallback();
00118 
00123     virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent& event);
00124 
00130     virtual void subscribe() = 0;
00131 
00137     virtual void unsubscribe() = 0;
00138 
00151     template<class T> ros::Publisher
00152     advertise(ros::NodeHandle& nh,
00153               std::string topic, int queue_size)
00154     {
00155       boost::mutex::scoped_lock lock(connection_mutex_);
00156       ros::SubscriberStatusCallback connect_cb
00157         = boost::bind(&Nodelet::connectionCallback, this, _1);
00158       ros::SubscriberStatusCallback disconnect_cb
00159         = 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,
00163                                            connect_cb,
00164                                            disconnect_cb,
00165                                            ros::VoidConstPtr(),
00166                                            latch);
00167       publishers_.push_back(ret);
00168       
00169       return ret;
00170     }
00171 
00184     image_transport::Publisher
00185     advertiseImage(ros::NodeHandle& nh,
00186                    const std::string& topic,
00187                    int queue_size)
00188     {
00189       boost::mutex::scoped_lock lock(connection_mutex_);
00190       image_transport::SubscriberStatusCallback connect_cb
00191         = boost::bind(&Nodelet::imageConnectionCallback,
00192                       this, _1);
00193       image_transport::SubscriberStatusCallback disconnect_cb
00194         = boost::bind(&Nodelet::imageConnectionCallback,
00195                       this, _1);
00196       bool latch;
00197       nh.param("latch", latch, false);
00198       image_transport::Publisher pub
00199         = image_transport::ImageTransport(nh).advertise(
00200           topic, 1,
00201           connect_cb, disconnect_cb,
00202           ros::VoidPtr(), latch);
00203       image_publishers_.push_back(pub);
00204       return pub;
00205     }
00206 
00220     image_transport::CameraPublisher
00221     advertiseCamera(ros::NodeHandle& nh,
00222                     const std::string& topic,
00223                     int queue_size)
00224     {
00225       boost::mutex::scoped_lock lock(connection_mutex_);
00226       image_transport::SubscriberStatusCallback connect_cb
00227         = boost::bind(&Nodelet::cameraConnectionCallback,
00228                       this, _1);
00229       image_transport::SubscriberStatusCallback disconnect_cb
00230         = boost::bind(&Nodelet::cameraConnectionCallback,
00231                       this, _1);
00232       ros::SubscriberStatusCallback info_connect_cb
00233         = boost::bind(&Nodelet::cameraInfoConnectionCallback,
00234                       this, _1);
00235       ros::SubscriberStatusCallback info_disconnect_cb
00236         = boost::bind(&Nodelet::cameraInfoConnectionCallback,
00237                       this, _1);
00238       bool latch;
00239       nh.param("latch", latch, false);
00240       image_transport::CameraPublisher
00241         pub = image_transport::ImageTransport(nh).advertiseCamera(topic, 1,
00242                                                                   connect_cb, disconnect_cb,
00243                                                                   info_connect_cb, info_disconnect_cb,
00244                                                                   ros::VoidPtr(),
00245                                                                   latch);
00246       camera_publishers_.push_back(pub);
00247       return pub;
00248     }
00249     
00254     boost::mutex connection_mutex_;
00255     
00259     std::vector<ros::Publisher> publishers_;
00260 
00264     std::vector<image_transport::Publisher> image_publishers_;
00265 
00269     std::vector<image_transport::CameraPublisher> camera_publishers_;
00270 
00274     boost::shared_ptr<ros::NodeHandle> nh_;
00275 
00279     boost::shared_ptr<ros::NodeHandle> pnh_;
00280 
00284     ros::WallTimer timer_;
00285 
00290     bool subscribed_;
00291 
00296     bool ever_subscribed_;
00297 
00302     bool always_subscribe_;
00303 
00307     ConnectionStatus connection_status_;
00308 
00312     bool verbose_connection_;
00313   private:
00314     
00315   };
00316 }
00317 
00318 #endif


opencv_apps
Author(s): Kei Okada
autogenerated on Tue May 2 2017 02:58:58