28 #ifndef ROSCPP_PUBLISHER_HANDLE_H 29 #define ROSCPP_PUBLISHER_HANDLE_H 32 #include "ros/common.h" 35 #include <boost/bind.hpp> 65 using namespace serialization;
69 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher");
73 if (!impl_->isValid())
75 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
79 ROS_ASSERT_MSG(impl_->md5sum_ ==
"*" || std::string(mt::md5sum<M>(*message)) ==
"*" || impl_->md5sum_ == mt::md5sum<M>(*message),
80 "Trying to publish message of type [%s/%s] on a publisher with type [%s/%s]",
81 mt::datatype<M>(*message), mt::md5sum<M>(*message),
82 impl_->datatype_.c_str(), impl_->md5sum_.c_str());
88 publish(boost::bind(serializeMessage<M>, boost::ref(*message)), m);
97 using namespace serialization;
102 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher");
106 if (!impl_->isValid())
108 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
112 ROS_ASSERT_MSG(impl_->md5sum_ ==
"*" || std::string(mt::md5sum<M>(message)) ==
"*" || impl_->md5sum_ == mt::md5sum<M>(message),
113 "Trying to publish message of type [%s/%s] on a publisher with type [%s/%s]",
114 mt::datatype<M>(message), mt::md5sum<M>(message),
115 impl_->datatype_.c_str(), impl_->md5sum_.c_str());
118 publish(boost::bind(serializeMessage<M>, boost::ref(message)), m);
136 std::string getTopic()
const;
141 uint32_t getNumSubscribers()
const;
146 bool isLatched()
const;
148 operator void*()
const {
return (impl_ && impl_->isValid()) ? (
void*)1 : (
void*)0; }
152 return impl_ < rhs.
impl_;
157 return impl_ == rhs.
impl_;
162 return impl_ != rhs.
impl_;
172 void incrementSequence()
const;
181 bool isValid()
const;
202 #endif // ROSCPP_PUBLISHER_HANDLE_H bool operator!=(const Publisher &rhs) const
boost::weak_ptr< Impl > ImplWPtr
void publish(const boost::shared_ptr< M > &message) const
Publish a message on the topic associated with this Publisher.
NodeHandlePtr node_handle_
bool operator<(const Publisher &rhs) const
const std::type_info * type_info
#define ROS_ASSERT_MSG(cond,...)
roscpp's interface for creating subscribers, publishers, etc.
void publish(const M &message) const
Publish a message on the topic associated with this Publisher.
Manages an advertisement on a specific topic.
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
bool operator==(const Publisher &rhs) const