Go to the documentation of this file.
41 ROS_DEBUG(
"Publisher on '%s' deregistering callbacks.", topic_.c_str());
47 return !unadvertised_;
61 boost::mutex::scoped_lock lock(last_message_mutex_);
62 if (last_message_.buf) {
63 sub_link->enqueueMessage(last_message_,
true,
true);
70 impl_->topic_ = topic;
73 impl_->latch_ = latch;
74 impl_->node_handle_ = boost::make_shared<NodeHandle>(node_handle);
75 impl_->callbacks_ = callbacks;
91 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher (topic [%s])",
impl_->topic_.c_str());
95 if (!
impl_->isValid())
97 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher (topic [%s])",
impl_->topic_.c_str());
104 boost::mutex::scoped_lock lock(
impl_->last_message_mutex_);
105 impl_->last_message_ = m;
121 impl_->unadvertise();
130 return impl_->topic_;
133 return std::string();
148 return impl_->latch_;
150 ROS_ASSERT_MSG(
false,
"Call to isLatched() on an invalid Publisher");
151 throw ros::Exception(
"Call to isLatched() on an invalid Publisher");
bool isLatched() const
Returns whether or not this topic is latched.
void publish(const boost::shared_ptr< M > &message) const
Publish a message on the topic associated with this Publisher.
void shutdown()
Shutdown the advertisement associated with this Publisher.
#define ROS_ASSERT_MSG(cond,...)
roscpp's interface for creating subscribers, publishers, etc.
Manages an advertisement on a specific topic.
std::string getTopic() const
Returns the topic that this Publisher will publish on.
void pushLastMessage(const SubscriberLinkPtr &sub_link)
static const TopicManagerPtr & instance()
uint32_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this Publisher.
void incrementSequence() const
roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
, Jacob Perron
autogenerated on Sat Sep 14 2024 02:59:35