publisher.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009, Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #include "ros/publisher.h"
29 #include "ros/publication.h"
30 #include "ros/node_handle.h"
31 #include "ros/subscriber_link.h"
32 #include "ros/topic_manager.h"
33 
34 namespace ros
35 {
36 
37 Publisher::Impl::Impl() : unadvertised_(false) { }
38 
40 {
41  ROS_DEBUG("Publisher on '%s' deregistering callbacks.", topic_.c_str());
42  unadvertise();
43 }
44 
46 {
47  return !unadvertised_;
48 }
49 
51 {
52  if (!unadvertised_)
53  {
54  unadvertised_ = true;
55  TopicManager::instance()->unadvertise(topic_, callbacks_);
56  node_handle_.reset();
57  }
58 }
59 
61  boost::mutex::scoped_lock lock(last_message_mutex_);
62  if (last_message_.buf) {
63  sub_link->enqueueMessage(last_message_, true, true);
64  }
65 }
66 
67 Publisher::Publisher(const std::string& topic, const std::string& md5sum, const std::string& datatype, bool latch, const NodeHandle& node_handle, const SubscriberCallbacksPtr& callbacks)
68 : impl_(boost::make_shared<Impl>())
69 {
70  impl_->topic_ = topic;
71  impl_->md5sum_ = md5sum;
72  impl_->datatype_ = datatype;
73  impl_->latch_ = latch;
74  impl_->node_handle_ = boost::make_shared<NodeHandle>(node_handle);
75  impl_->callbacks_ = callbacks;
76 }
77 
79 {
80  impl_ = rhs.impl_;
81 }
82 
84 {
85 }
86 
87 void Publisher::publish(const boost::function<SerializedMessage(void)>& serfunc, SerializedMessage& m) const
88 {
89  if (!impl_)
90  {
91  ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
92  return;
93  }
94 
95  if (!impl_->isValid())
96  {
97  ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
98  return;
99  }
100 
101  TopicManager::instance()->publish(impl_->topic_, serfunc, m);
102 
103  if (isLatched()) {
104  boost::mutex::scoped_lock lock(impl_->last_message_mutex_);
105  impl_->last_message_ = m;
106  }
107 }
108 
110 {
111  if (impl_ && impl_->isValid())
112  {
113  TopicManager::instance()->incrementSequence(impl_->topic_);
114  }
115 }
116 
118 {
119  if (impl_)
120  {
121  impl_->unadvertise();
122  impl_.reset();
123  }
124 }
125 
126 std::string Publisher::getTopic() const
127 {
128  if (impl_)
129  {
130  return impl_->topic_;
131  }
132 
133  return std::string();
134 }
135 
137 {
138  if (impl_ && impl_->isValid())
139  {
140  return TopicManager::instance()->getNumSubscribers(impl_->topic_);
141  }
142 
143  return 0;
144 }
145 
146 bool Publisher::isLatched() const {
147  if (impl_ && impl_->isValid()) {
148  return impl_->latch_;
149  } else {
150  ROS_ASSERT_MSG(false, "Call to isLatched() on an invalid Publisher");
151  throw ros::Exception("Call to isLatched() on an invalid Publisher");
152  }
153 }
154 
155 } // namespace ros
ros::SerializedMessage
md5sum
const char * md5sum()
ros::Publisher::Impl
Definition: publisher.h:186
boost::shared_ptr< SubscriberLink >
ros::Publisher::isLatched
bool isLatched() const
Returns whether or not this topic is latched.
Definition: publisher.cpp:146
ros
ros::Publisher::Impl::unadvertise
void unadvertise()
Definition: publisher.cpp:50
boost
ros::Exception
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
Publish a message on the topic associated with this Publisher.
Definition: publisher.h:65
ros::Publisher::impl_
ImplPtr impl_
Definition: publisher.h:209
topic_manager.h
ros::Publisher::shutdown
void shutdown()
Shutdown the advertisement associated with this Publisher.
Definition: publisher.cpp:117
ROS_DEBUG
#define ROS_DEBUG(...)
ros::Publisher::Impl::~Impl
~Impl()
Definition: publisher.cpp:39
ros::Publisher::~Publisher
~Publisher()
Definition: publisher.cpp:83
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
ros::NodeHandle
roscpp's interface for creating subscribers, publishers, etc.
Definition: node_handle.h:87
publisher.h
ros::Publisher
Manages an advertisement on a specific topic.
Definition: publisher.h:48
ros::Publisher::getTopic
std::string getTopic() const
Returns the topic that this Publisher will publish on.
Definition: publisher.cpp:126
ros::Publisher::Impl::pushLastMessage
void pushLastMessage(const SubscriberLinkPtr &sub_link)
Definition: publisher.cpp:60
ros::Publisher::Impl::Impl
Impl()
Definition: publisher.cpp:37
ros::Publisher::Publisher
Publisher()
Definition: publisher.h:51
ros::Publisher::Impl::isValid
bool isValid() const
Definition: publisher.cpp:45
ros::TopicManager::instance
static const TopicManagerPtr & instance()
Definition: topic_manager.cpp:56
publication.h
datatype
const char * datatype()
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this Publisher.
Definition: publisher.cpp:136
ros::Publisher::incrementSequence
void incrementSequence() const
Definition: publisher.cpp:109
node_handle.h


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:44