nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2016, Ryohei Ueda.
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 #include "opencv_apps/nodelet.h"
00037 
00038 namespace opencv_apps
00039 {
00040 void Nodelet::onInit()
00041 {
00042   connection_status_ = NOT_SUBSCRIBED;
00043   nh_.reset(new ros::NodeHandle(getMTNodeHandle()));
00044   pnh_.reset(new ros::NodeHandle(getMTPrivateNodeHandle()));
00045   pnh_->param("always_subscribe", always_subscribe_, false);
00046   pnh_->param("verbose_connection", verbose_connection_, false);
00047   if (!verbose_connection_)
00048   {
00049     nh_->param("verbose_connection", verbose_connection_, false);
00050   }
00051   // timer to warn when no connection in a few seconds
00052   ever_subscribed_ = false;
00053   timer_ = nh_->createWallTimer(ros::WallDuration(5), &Nodelet::warnNeverSubscribedCallback, this,
00054                                 /*oneshot=*/true);
00055 }
00056 
00057 void Nodelet::onInitPostProcess()
00058 {
00059   if (always_subscribe_)
00060   {
00061     subscribe();
00062   }
00063 }
00064 
00065 void Nodelet::warnNeverSubscribedCallback(const ros::WallTimerEvent& event)
00066 {
00067   if (!ever_subscribed_)
00068   {
00069     NODELET_WARN("'%s' subscribes topics only with child subscribers.", nodelet::Nodelet::getName().c_str());
00070   }
00071 }
00072 
00073 void Nodelet::connectionCallback(const ros::SingleSubscriberPublisher& pub)
00074 {
00075   if (verbose_connection_)
00076   {
00077     NODELET_INFO("New connection or disconnection is detected");
00078   }
00079   if (!always_subscribe_)
00080   {
00081     boost::mutex::scoped_lock lock(connection_mutex_);
00082     for (const ros::Publisher& pub : publishers_)
00083     {
00084       if (pub.getNumSubscribers() > 0)
00085       {
00086         if (!ever_subscribed_)
00087         {
00088           ever_subscribed_ = true;
00089         }
00090         if (connection_status_ != SUBSCRIBED)
00091         {
00092           if (verbose_connection_)
00093           {
00094             NODELET_INFO("Subscribe input topics");
00095           }
00096           subscribe();
00097           connection_status_ = SUBSCRIBED;
00098         }
00099         return;
00100       }
00101     }
00102     if (connection_status_ == SUBSCRIBED)
00103     {
00104       if (verbose_connection_)
00105       {
00106         NODELET_INFO("Unsubscribe input topics");
00107       }
00108       unsubscribe();
00109       connection_status_ = NOT_SUBSCRIBED;
00110     }
00111   }
00112 }
00113 
00114 void Nodelet::imageConnectionCallback(const image_transport::SingleSubscriberPublisher& pub)
00115 {
00116   if (verbose_connection_)
00117   {
00118     NODELET_INFO("New image connection or disconnection is detected");
00119   }
00120   if (!always_subscribe_)
00121   {
00122     boost::mutex::scoped_lock lock(connection_mutex_);
00123     for (const image_transport::Publisher& pub : image_publishers_)
00124     {
00125       if (pub.getNumSubscribers() > 0)
00126       {
00127         if (!ever_subscribed_)
00128         {
00129           ever_subscribed_ = true;
00130         }
00131         if (connection_status_ != SUBSCRIBED)
00132         {
00133           if (verbose_connection_)
00134           {
00135             NODELET_INFO("Subscribe input topics");
00136           }
00137           subscribe();
00138           connection_status_ = SUBSCRIBED;
00139         }
00140         return;
00141       }
00142     }
00143     if (connection_status_ == SUBSCRIBED)
00144     {
00145       if (verbose_connection_)
00146       {
00147         NODELET_INFO("Unsubscribe input topics");
00148       }
00149       unsubscribe();
00150       connection_status_ = NOT_SUBSCRIBED;
00151     }
00152   }
00153 }
00154 
00155 void Nodelet::cameraConnectionCallback(const image_transport::SingleSubscriberPublisher& pub)
00156 {
00157   cameraConnectionBaseCallback();
00158 }
00159 
00160 void Nodelet::cameraInfoConnectionCallback(const ros::SingleSubscriberPublisher& pub)
00161 {
00162   cameraConnectionBaseCallback();
00163 }
00164 
00165 void Nodelet::cameraConnectionBaseCallback()
00166 {
00167   if (verbose_connection_)
00168   {
00169     NODELET_INFO("New image connection or disconnection is detected");
00170   }
00171   if (!always_subscribe_)
00172   {
00173     boost::mutex::scoped_lock lock(connection_mutex_);
00174     for (const image_transport::CameraPublisher& pub : camera_publishers_)
00175     {
00176       if (pub.getNumSubscribers() > 0)
00177       {
00178         if (!ever_subscribed_)
00179         {
00180           ever_subscribed_ = true;
00181         }
00182         if (connection_status_ != SUBSCRIBED)
00183         {
00184           if (verbose_connection_)
00185           {
00186             NODELET_INFO("Subscribe input topics");
00187           }
00188           subscribe();
00189           connection_status_ = SUBSCRIBED;
00190         }
00191         return;
00192       }
00193     }
00194     if (connection_status_ == SUBSCRIBED)
00195     {
00196       if (verbose_connection_)
00197       {
00198         NODELET_INFO("Unsubscribe input topics");
00199       }
00200       unsubscribe();
00201       connection_status_ = NOT_SUBSCRIBED;
00202     }
00203   }
00204 }
00205 }  // namespace opencv_apps


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