28 #ifndef ROSCPP_PUBLISHER_HANDLE_H
29 #define ROSCPP_PUBLISHER_HANDLE_H
32 #include "ros/common.h"
35 #include <boost/bind.hpp>
36 #include <boost/thread/mutex.hpp>
67 using namespace serialization;
71 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher");
75 if (!impl_->isValid())
77 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
80 if (impl_->md5sum_ ==
"*" ||
81 std::string(mt::md5sum<M>(*message)) ==
"*" ||
82 impl_->md5sum_ == mt::md5sum<M>(*message)) {
84 "publisher with type [%s/%s]",
85 mt::datatype<M>(*message), mt::md5sum<M>(*message),
86 impl_->datatype_.c_str(), impl_->md5sum_.c_str());
93 publish(boost::bind(serializeMessage<M>, boost::ref(*message)), m);
102 using namespace serialization;
107 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher");
111 if (!impl_->isValid())
113 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
116 if (impl_->md5sum_ ==
"*" ||
117 std::string(mt::md5sum<M>(message)) ==
"*" ||
118 impl_->md5sum_ == mt::md5sum<M>(message)) {
120 "publisher with type [%s/%s]",
121 mt::datatype<M>(message), mt::md5sum<M>(message),
122 impl_->datatype_.c_str(), impl_->md5sum_.c_str());
126 publish(boost::bind(serializeMessage<M>, boost::ref(message)), m);
144 std::string getTopic()
const;
149 uint32_t getNumSubscribers()
const;
154 bool isLatched()
const;
156 operator void*()
const {
return (impl_ && impl_->isValid()) ? (
void*)1 : (
void*)0; }
160 return impl_ < rhs.
impl_;
165 return impl_ == rhs.
impl_;
170 return impl_ != rhs.
impl_;
174 return boost::bind(&Impl::pushLastMessage, impl_.get(), boost::placeholders::_1);
179 Publisher(
const std::string& topic,
const std::string& md5sum,
180 const std::string& datatype,
bool latch,
const NodeHandle& node_handle,
184 void incrementSequence()
const;
193 bool isValid()
const;
218 #endif // ROSCPP_PUBLISHER_HANDLE_H