Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
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_(boost::make_shared<Impl>())
00061 {
00062 impl_->topic_ = topic;
00063 impl_->md5sum_ = md5sum;
00064 impl_->datatype_ = datatype;
00065 impl_->node_handle_ = boost::make_shared<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 }
roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Tue Mar 7 2017 03:44:47