lightweight_throttle_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, 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 Willow Garage 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 #include <pluginlib/class_list_macros.h>
00036 #include "jsk_topic_tools/lightweight_throttle_nodelet.h"
00037 
00038 namespace jsk_topic_tools
00039 {
00040   void LightweightThrottle::onInit()
00041   {
00042     pnh_ = this->getPrivateNodeHandle();
00043     latest_stamp_ = ros::Time::now();
00044     advertised_ = false;
00045     subscribing_ = false;
00046     pnh_.param("update_rate", update_rate_, 1.0); // default 1.0
00047     sub_.reset(new ros::Subscriber(
00048                  pnh_.subscribe<topic_tools::ShapeShifter>("input", 1,
00049                                                            &LightweightThrottle::inCallback,
00050                                                            this,
00051                                                            th_)));
00052   }
00053 
00054   void LightweightThrottle::connectionCallback(
00055     const ros::SingleSubscriberPublisher& pub)
00056   {
00057     if (pub_.getNumSubscribers() > 0) {
00058       if (!subscribing_) {
00059         sub_.reset(new ros::Subscriber(
00060                      pnh_.subscribe<topic_tools::ShapeShifter>(
00061                        "input", 1,
00062                        &LightweightThrottle::inCallback,
00063                        this,
00064                        th_)));
00065         subscribing_ = false;
00066       }
00067     }
00068     else {
00069       if (subscribing_) {
00070         sub_->shutdown();
00071         subscribing_ = true;
00072       }
00073     }
00074   }
00075   
00076   void LightweightThrottle::inCallback(
00077     const boost::shared_ptr<topic_tools::ShapeShifter const>& msg)
00078   {
00079     // advertise if not
00080     if (!advertised_) {
00081       ros::SubscriberStatusCallback connect_cb
00082         = boost::bind(&LightweightThrottle::connectionCallback, this, _1);
00083       ros::AdvertiseOptions opts("output", 1,
00084                                  msg->getMD5Sum(),
00085                                  msg->getDataType(),
00086                                  msg->getMessageDefinition(),
00087                                  connect_cb,
00088                                  connect_cb);
00089       pub_ = pnh_.advertise(opts);
00090       advertised_ = true;
00091       sub_->shutdown();
00092     }
00093     ros::Time now = ros::Time::now();
00094     if ((now - latest_stamp_).toSec() > 1 / update_rate_) {
00095       // publish the message to output topic only if any
00096       // subscriber is
00097       if (pub_.getNumSubscribers()) {
00098         pub_.publish(msg);
00099       }
00100       latest_stamp_ = now;
00101     }
00102   }
00103 }
00104 
00105 typedef jsk_topic_tools::LightweightThrottle LightweightThrottle;
00106 PLUGINLIB_EXPORT_CLASS(LightweightThrottle, nodelet::Nodelet)


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Mon Oct 6 2014 10:56:17