publisher.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2009, Willow Garage, Inc.
00003  *
00004  * Redistribution and use in source and binary forms, with or without
00005  * modification, are permitted provided that the following conditions are met:
00006  *   * Redistributions of source code must retain the above copyright notice,
00007  *     this list of conditions and the following disclaimer.
00008  *   * Redistributions in binary form must reproduce the above copyright
00009  *     notice, this list of conditions and the following disclaimer in the
00010  *     documentation and/or other materials provided with the distribution.
00011  *   * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
00012  *     contributors may be used to endorse or promote products derived from
00013  *     this software without specific prior written permission.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
00026  */
00027 
00028 #include "ros/publisher.h"
00029 #include "ros/publication.h"
00030 #include "ros/node_handle.h"
00031 #include "ros/topic_manager.h"
00032 
00033 namespace ros
00034 {
00035 
00036 Publisher::Impl::Impl() : unadvertised_(false) { }
00037 
00038 Publisher::Impl::~Impl()
00039 {
00040   ROS_DEBUG("Publisher on '%s' deregistering callbacks.", topic_.c_str());
00041   unadvertise();
00042 }
00043 
00044 bool Publisher::Impl::isValid() const
00045 {
00046   return !unadvertised_;
00047 }
00048 
00049 void Publisher::Impl::unadvertise()
00050 {
00051   if (!unadvertised_)
00052   {
00053     unadvertised_ = true;
00054     TopicManager::instance()->unadvertise(topic_, callbacks_);
00055     node_handle_.reset();
00056   }
00057 }
00058 
00059 Publisher::Publisher(const std::string& topic, const std::string& md5sum, const std::string& datatype, const NodeHandle& node_handle, const SubscriberCallbacksPtr& callbacks)
00060 : impl_(new Impl)
00061 {
00062   impl_->topic_ = topic;
00063   impl_->md5sum_ = md5sum;
00064   impl_->datatype_ = datatype;
00065   impl_->node_handle_ = NodeHandlePtr(new NodeHandle(node_handle));
00066   impl_->callbacks_ = callbacks;
00067 }
00068 
00069 Publisher::Publisher(const Publisher& rhs)
00070 {
00071   impl_ = rhs.impl_;
00072 }
00073 
00074 Publisher::~Publisher()
00075 {
00076 }
00077 
00078 void Publisher::publish(const boost::function<SerializedMessage(void)>& serfunc, SerializedMessage& m) const
00079 {
00080   if (!impl_)
00081   {
00082     ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
00083     return;
00084   }
00085 
00086   if (!impl_->isValid())
00087   {
00088     ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
00089     return;
00090   }
00091 
00092   TopicManager::instance()->publish(impl_->topic_, serfunc, m);
00093 }
00094 
00095 void Publisher::incrementSequence() const
00096 {
00097   if (impl_ && impl_->isValid())
00098   {
00099     TopicManager::instance()->incrementSequence(impl_->topic_);
00100   }
00101 }
00102 
00103 void Publisher::shutdown()
00104 {
00105   if (impl_)
00106   {
00107     impl_->unadvertise();
00108     impl_.reset();
00109   }
00110 }
00111 
00112 std::string Publisher::getTopic() const
00113 {
00114   if (impl_)
00115   {
00116     return impl_->topic_;
00117   }
00118 
00119   return std::string();
00120 }
00121 
00122 uint32_t Publisher::getNumSubscribers() const
00123 {
00124   if (impl_ && impl_->isValid())
00125   {
00126     return TopicManager::instance()->getNumSubscribers(impl_->topic_);
00127   }
00128 
00129   return 0;
00130 }
00131 
00132 bool Publisher::isLatched() const {
00133   PublicationPtr publication_ptr;
00134   if (impl_ && impl_->isValid()) {
00135     publication_ptr =
00136       TopicManager::instance()->lookupPublication(impl_->topic_);
00137   } else {
00138     ROS_ASSERT_MSG(false, "Call to isLatched() on an invalid Publisher");
00139     throw ros::Exception("Call to isLatched() on an invalid Publisher");
00140   }
00141   if (publication_ptr) {
00142     return publication_ptr->isLatched();
00143   } else {
00144     ROS_ASSERT_MSG(false, "Call to isLatched() on an invalid Publisher");
00145     throw ros::Exception("Call to isLatched() on an invalid Publisher");
00146   }
00147 }
00148 
00149 } // namespace ros


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Mon Oct 6 2014 11:46:44