00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef ROSCPP_PUBLISHER_HANDLE_H
00029 #define ROSCPP_PUBLISHER_HANDLE_H
00030
00031 #include "ros/forwards.h"
00032 #include "ros/common.h"
00033 #include "ros/message.h"
00034 #include "ros/serialization.h"
00035 #include <boost/bind.hpp>
00036
00037 namespace ros
00038 {
00039
00048 class Publisher
00049 {
00050 public:
00051 Publisher() {}
00052 Publisher(const Publisher& rhs);
00053 ~Publisher();
00054
00063 template<typename M>
00064 void publish(const boost::shared_ptr<M>& message) const
00065 {
00066 using namespace serialization;
00067
00068 if (!impl_)
00069 {
00070 ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
00071 return;
00072 }
00073
00074 if (!impl_->isValid())
00075 {
00076 ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
00077 return;
00078 }
00079
00080 ROS_ASSERT_MSG(impl_->md5sum_ != "*" || impl_->md5sum_ == mt::md5sum<M>(*message), "Trying to publish message of type [%s/%s] on a publisher with type [%s/%s]",
00081 impl_->datatype_.c_str(), impl_->md5sum_.c_str(), mt::datatype<M>(*message), mt::md5sum<M>(*message));
00082
00083 SerializedMessage m;
00084 m.type_info = &typeid(M);
00085 m.message = message;
00086
00087 publish(boost::bind(serializeMessage<M>, boost::ref(*message)), m);
00088 }
00089
00093 template<typename M>
00094 void publish(const M& message) const
00095 {
00096 using namespace serialization;
00097 namespace mt = ros::message_traits;
00098
00099 if (!impl_)
00100 {
00101 ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
00102 return;
00103 }
00104
00105 if (!impl_->isValid())
00106 {
00107 ROS_ASSERT_MSG(false, "Call to publish() on an invalid Publisher (topic [%s])", impl_->topic_.c_str());
00108 return;
00109 }
00110
00111 ROS_ASSERT_MSG(impl_->md5sum_ != "*" || impl_->md5sum_ == mt::md5sum<M>(message), "Trying to publish message of type [%s/%s] on a publisher with type [%s/%s]",
00112 impl_->datatype_.c_str(), impl_->md5sum_.c_str(), mt::datatype<M>(message), mt::md5sum<M>(message));
00113
00114 SerializedMessage m;
00115 publish(boost::bind(serializeMessage<M>, boost::ref(message)), m);
00116 }
00117
00128 void shutdown();
00129
00133 std::string getTopic() const;
00134
00138 uint32_t getNumSubscribers() const;
00139
00143 bool isLatched() const;
00144
00145 operator void*() const { return (impl_ && impl_->isValid()) ? (void*)1 : (void*)0; }
00146
00147 bool operator<(const Publisher& rhs) const
00148 {
00149 return impl_ < rhs.impl_;
00150 }
00151
00152 bool operator==(const Publisher& rhs) const
00153 {
00154 return impl_ == rhs.impl_;
00155 }
00156
00157 bool operator!=(const Publisher& rhs) const
00158 {
00159 return impl_ != rhs.impl_;
00160 }
00161
00162 private:
00163 Publisher(const std::string& topic, const std::string& md5sum, const std::string& datatype, const NodeHandle& node_handle, const SubscriberCallbacksPtr& callbacks);
00164
00165 void publish(const boost::function<SerializedMessage(void)>& serfunc, SerializedMessage& m) const;
00166 void incrementSequence() const;
00167
00168 class Impl
00169 {
00170 public:
00171 Impl();
00172 ~Impl();
00173
00174 void unadvertise();
00175 bool isValid() const;
00176
00177 std::string topic_;
00178 std::string md5sum_;
00179 std::string datatype_;
00180 NodeHandlePtr node_handle_;
00181 SubscriberCallbacksPtr callbacks_;
00182 bool unadvertised_;
00183 double constructed_;
00184 };
00185 typedef boost::shared_ptr<Impl> ImplPtr;
00186 typedef boost::weak_ptr<Impl> ImplWPtr;
00187
00188 ImplPtr impl_;
00189
00190 friend class NodeHandle;
00191 friend class NodeHandleBackingCollection;
00192 };
00193 typedef std::vector<Publisher> V_Publisher;
00194
00195 }
00196
00197 #endif // ROSCPP_PUBLISHER_HANDLE_H
00198