passthrough_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2014, JSK Lab
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/o2r other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the JSK Lab 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 #include <pluginlib/class_list_macros.h>
00035 #include "jsk_topic_tools/passthrough_nodelet.h"
00036 
00037 namespace jsk_topic_tools
00038 {
00053   void Passthrough::onInit()
00054   {
00055     advertised_ = false;
00056     publish_requested_ = false;
00057     pnh_ = getPrivateNodeHandle();
00058     subscribing_ = true;
00059     pnh_.param("default_duration", default_duration_, 10.0);
00060     sub_ = pnh_.subscribe<topic_tools::ShapeShifter>(
00061       "input", 1,
00062       &Passthrough::inputCallback, this);
00063     request_duration_srv_ = pnh_.advertiseService(
00064       "request_duration", &Passthrough::requestDurationCallback, this);
00065     request_srv_ = pnh_.advertiseService(
00066       "request", &Passthrough::requestCallback, this);
00067     stop_srv_ = pnh_.advertiseService(
00068       "stop", &Passthrough::stopCallback, this);
00069   }
00070 
00071   bool Passthrough::stopCallback(
00072     std_srvs::Empty::Request &req,
00073     std_srvs::Empty::Response &res)
00074   {
00075     boost::mutex::scoped_lock lock(mutex_);
00076     // force to stop publishing
00077     if (!publish_requested_) {
00078       NODELET_DEBUG("already stoppped");
00079     }
00080     publish_requested_ = false;
00081     return true;
00082   }
00083 
00084   void Passthrough::requestDurationCallbackImpl(
00085     const ros::Duration& duration)
00086   {
00087     boost::mutex::scoped_lock lock(mutex_);
00088     // special case of ros::Duration(0), it means eternal
00089     if (duration == ros::Duration(0)) {
00090       end_time_ = ros::Time(0);
00091       publish_requested_ = true;
00092     }
00093     else {
00094       ros::Time now = ros::Time::now();
00095       if (publish_requested_) {
00096         // check need to update end_time or not
00097         if (end_time_ < now + duration) {
00098           end_time_ = now + duration;
00099         }
00100       }
00101       else {
00102         publish_requested_ = true;
00103         end_time_ = now + duration;
00104       }
00105     }
00106     if (!subscribing_) {
00107       NODELET_DEBUG("suscribe");
00108       sub_ = pnh_.subscribe<topic_tools::ShapeShifter>(
00109         "input", 1,
00110         &Passthrough::inputCallback, this);
00111       subscribing_ = true;
00112     }
00113   }
00114   
00115   bool Passthrough::requestDurationCallback(
00116     jsk_topic_tools::PassthroughDuration::Request &req,
00117     jsk_topic_tools::PassthroughDuration::Response &res)
00118   {
00119     requestDurationCallbackImpl(req.duration);
00120     return true;
00121   }
00122 
00123   bool Passthrough::requestCallback(
00124     std_srvs::Empty::Request &req,
00125     std_srvs::Empty::Response &res)
00126   {
00127     requestDurationCallbackImpl(ros::Duration(default_duration_));
00128     return true;
00129   }
00130   
00131   void Passthrough::inputCallback(
00132     const boost::shared_ptr<topic_tools::ShapeShifter const>& msg)
00133   {
00134     boost::mutex::scoped_lock lock(mutex_);
00135     if (!advertised_) {
00136       // this block is called only once
00137       // in order to advertise topic.
00138       // we need to subscribe at least one message
00139       // in order to detect message definition.
00140       pub_ = advertise(msg, "output");
00141       advertised_ = true;
00142     }
00143     if (publish_requested_) {
00144       ros::Time now = ros::Time::now();
00145       if (end_time_ == ros::Time(0) || // ros::Time(0) means eternal publishing
00146           end_time_ > now) {
00147         pub_.publish(msg);
00148       }
00149       // check it goes over end_time_ 
00150       if (end_time_ != ros::Time(0) && end_time_ < now) {
00151         publish_requested_ = false;
00152       }
00153     }
00154     if (!publish_requested_) {
00155       // Unsubscribe input anyway
00156       sub_.shutdown();
00157       subscribing_ = false;
00158     }
00159   }
00160 
00161   void Passthrough::connectCb()
00162   {
00163     boost::mutex::scoped_lock lock(mutex_);
00164     NODELET_DEBUG("connectCB");
00165     if (advertised_) {
00166       if (pub_.getNumSubscribers() > 0) {
00167         if (!subscribing_ && publish_requested_) {
00168           NODELET_DEBUG("suscribe");
00169           sub_ = pnh_.subscribe<topic_tools::ShapeShifter>(
00170             "input", 1,
00171             &Passthrough::inputCallback, this);
00172           subscribing_ = true;
00173         }
00174       }
00175     }
00176   }
00177 
00178   void Passthrough::disconnectCb()
00179   {
00180     boost::mutex::scoped_lock lock(mutex_);
00181     NODELET_DEBUG("disconnectCb");
00182     if (advertised_) {
00183       if (pub_.getNumSubscribers() == 0) {
00184         if (subscribing_) {
00185           NODELET_DEBUG("disconnect");
00186           sub_.shutdown();
00187           subscribing_ = false;
00188         }
00189       }
00190     }
00191   }
00192 
00193   
00194   ros::Publisher Passthrough::advertise(
00195     boost::shared_ptr<topic_tools::ShapeShifter const> msg,
00196     const std::string& topic)
00197   {
00198     ros::SubscriberStatusCallback connect_cb
00199       = boost::bind( &Passthrough::connectCb, this);
00200     ros::SubscriberStatusCallback disconnect_cb
00201       = boost::bind( &Passthrough::disconnectCb, this);
00202     ros::AdvertiseOptions opts(topic, 1,
00203                                msg->getMD5Sum(),
00204                                msg->getDataType(),
00205                                msg->getMessageDefinition());
00206     opts.latch = true;
00207     return pnh_.advertise(opts);
00208   }
00209 }
00210 
00211 typedef jsk_topic_tools::Passthrough Passthrough;
00212 PLUGINLIB_EXPORT_CLASS(Passthrough, nodelet::Nodelet)


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