28 #ifndef ROSCPP_PUBLISHER_HANDLE_H
29 #define ROSCPP_PUBLISHER_HANDLE_H
32 #include "ros/common.h"
35 #include <boost/bind/bind.hpp>
36 #include <boost/thread/mutex.hpp>
39 using namespace boost::placeholders;
70 using namespace serialization;
74 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher");
78 if (!impl_->isValid())
80 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
83 if (impl_->md5sum_ ==
"*" ||
84 std::string(mt::md5sum<M>(*message)) ==
"*" ||
85 impl_->md5sum_ == mt::md5sum<M>(*message)) {
87 "publisher with type [%s/%s]",
88 mt::datatype<M>(*message), mt::md5sum<M>(*message),
89 impl_->datatype_.c_str(), impl_->md5sum_.c_str());
96 publish(boost::bind(serializeMessage<M>, boost::ref(*message)), m);
102 template <
typename M>
105 using namespace serialization;
110 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher");
114 if (!impl_->isValid())
116 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
119 if (impl_->md5sum_ ==
"*" ||
120 std::string(mt::md5sum<M>(message)) ==
"*" ||
121 impl_->md5sum_ == mt::md5sum<M>(message)) {
123 "publisher with type [%s/%s]",
124 mt::datatype<M>(message), mt::md5sum<M>(message),
125 impl_->datatype_.c_str(), impl_->md5sum_.c_str());
129 publish(boost::bind(serializeMessage<M>, boost::ref(message)), m);
147 std::string getTopic()
const;
152 uint32_t getNumSubscribers()
const;
157 bool isLatched()
const;
159 operator void*()
const {
return (impl_ && impl_->isValid()) ? (
void*)1 : (
void*)0; }
163 return impl_ < rhs.
impl_;
168 return impl_ == rhs.
impl_;
173 return impl_ != rhs.
impl_;
177 return boost::bind(&Impl::pushLastMessage, impl_.get(), boost::placeholders::_1);
182 Publisher(
const std::string& topic,
const std::string& md5sum,
183 const std::string& datatype,
bool latch,
const NodeHandle& node_handle,
187 void incrementSequence()
const;
196 bool isValid()
const;
221 #endif // ROSCPP_PUBLISHER_HANDLE_H