28 #ifndef ROSCPP_PUBLISHER_HANDLE_H 29 #define ROSCPP_PUBLISHER_HANDLE_H 32 #include "ros/common.h" 35 #include <boost/bind.hpp> 66 using namespace serialization;
70 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher");
74 if (!impl_->isValid())
76 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
79 if (impl_->md5sum_ ==
"*" ||
80 std::string(mt::md5sum<M>(*message)) ==
"*" ||
81 impl_->md5sum_ == mt::md5sum<M>(*message)) {
83 "publisher with type [%s/%s]",
84 mt::datatype<M>(*message), mt::md5sum<M>(*message),
85 impl_->datatype_.c_str(), impl_->md5sum_.c_str());
92 publish(boost::bind(serializeMessage<M>, boost::ref(*message)), m);
101 using namespace serialization;
106 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher");
110 if (!impl_->isValid())
112 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
115 if (impl_->md5sum_ ==
"*" ||
116 std::string(mt::md5sum<M>(message)) ==
"*" ||
117 impl_->md5sum_ == mt::md5sum<M>(message)) {
119 "publisher with type [%s/%s]",
120 mt::datatype<M>(message), mt::md5sum<M>(message),
121 impl_->datatype_.c_str(), impl_->md5sum_.c_str());
125 publish(boost::bind(serializeMessage<M>, boost::ref(message)), m);
143 std::string getTopic()
const;
148 uint32_t getNumSubscribers()
const;
153 bool isLatched()
const;
155 operator void*()
const {
return (impl_ && impl_->isValid()) ? (
void*)1 : (
void*)0; }
159 return impl_ < rhs.
impl_;
164 return impl_ == rhs.
impl_;
169 return impl_ != rhs.
impl_;
179 void incrementSequence()
const;
188 bool isValid()
const;
209 #endif // ROSCPP_PUBLISHER_HANDLE_H bool operator<(const Publisher &rhs) const
boost::weak_ptr< Impl > ImplWPtr
NodeHandlePtr node_handle_
void publish(const M &message) const
Publish a message on the topic associated with this Publisher.
#define ROS_DEBUG_ONCE(...)
bool operator!=(const Publisher &rhs) const
void publish(const boost::shared_ptr< M > &message) const
Publish a message on the topic associated with this Publisher.
const std::type_info * type_info
#define ROS_ASSERT_MSG(cond,...)
roscpp's interface for creating subscribers, publishers, etc.
Manages an advertisement on a specific topic.
bool operator==(const Publisher &rhs) const
SubscriberCallbacksPtr callbacks_
boost::shared_ptr< Impl > ImplPtr
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
std::vector< Publisher > V_Publisher