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 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 
00035 #include <jsk_topic_tools/lightweight_throttle_nodelet.h>
00036 
00037 namespace jsk_topic_tools
00038 {
00039   void LightweightThrottle::onInit()
00040   {
00041     pnh_ = this->getPrivateNodeHandle();
00042     latest_stamp_ = ros::Time::now();
00043     advertised_ = false;
00044     subscribing_ = false;
00045 
00046     srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(pnh_);
00047     dynamic_reconfigure::Server<Config>::CallbackType f =
00048       boost::bind(&LightweightThrottle::configCallback, this, _1, _2);
00049     srv_->setCallback(f);
00050 
00051     // Subscribe input topic at first in order to decide
00052     // message type of publisher.
00053     // nodelet will unsubscribe input topic after it receives the first topic.
00054     sub_.reset(new ros::Subscriber(
00055                  pnh_.subscribe<topic_tools::ShapeShifter>("input", 1,
00056                                                            &LightweightThrottle::inCallback,
00057                                                            this,
00058                                                            th_)));
00059   }
00060 
00061   void LightweightThrottle::configCallback(Config& config, uint32_t level)
00062   {
00063     boost::mutex::scoped_lock lock(mutex_);
00064     update_rate_ = config.update_rate;
00065   }
00066 
00067   void LightweightThrottle::connectionCallback(
00068     const ros::SingleSubscriberPublisher& pub)
00069   {
00070     if (pub_.getNumSubscribers() > 0) {
00071       if (!subscribing_) {
00072         sub_.reset(new ros::Subscriber(
00073                      pnh_.subscribe<topic_tools::ShapeShifter>(
00074                        "input", 1,
00075                        &LightweightThrottle::inCallback,
00076                        this,
00077                        th_)));
00078         subscribing_ = true;
00079       }
00080     }
00081     else {      // No subscribers, nodelet can unsubscribe input topic
00082       if (subscribing_) {
00083         sub_->shutdown();
00084         subscribing_ = false;
00085       }
00086     }
00087   }
00088   
00089   void LightweightThrottle::inCallback(
00090     const boost::shared_ptr<topic_tools::ShapeShifter const>& msg)
00091   {
00092     boost::mutex::scoped_lock lock(mutex_);
00093     // advertise if not
00094     if (!advertised_) {
00095       // This section should be called once
00096       sub_->shutdown();         // Shutdown before advertising topic
00097       ros::SubscriberStatusCallback connect_cb
00098         = boost::bind(&LightweightThrottle::connectionCallback, this, _1);
00099       ros::AdvertiseOptions opts("output", 1,
00100                                  msg->getMD5Sum(),
00101                                  msg->getDataType(),
00102                                  msg->getMessageDefinition(),
00103                                  connect_cb,
00104                                  connect_cb);
00105       advertised_ = true;
00106       pub_ = pnh_.advertise(opts);
00107     }
00108 
00109     ros::Time now = ros::Time::now();
00110 
00111     if (latest_stamp_ > now) {
00112       ROS_WARN("Detected jump back in time. latest_stamp_ is overwritten.");
00113       latest_stamp_ = now;
00114     }
00115 
00116     if (update_rate_ > 0.0 && (now - latest_stamp_).toSec() > 1.0 / update_rate_) {
00117       pub_.publish(msg);
00118       latest_stamp_ = now;
00119     }
00120   }
00121 }
00122 
00123 #include <pluginlib/class_list_macros.h>
00124 typedef jsk_topic_tools::LightweightThrottle LightweightThrottle;
00125 PLUGINLIB_EXPORT_CLASS(LightweightThrottle, nodelet::Nodelet)


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